ParameterExtraction.h
Go to the documentation of this file.
00001 /* ParameterExtraction.h - Parameter Extraction definitions header file */
00002 
00003 /*
00004 * Software License Agreement (BSD License) 
00005 *
00006 * Copyright (c) 2011, Yaskawa America, Inc.
00007 * All rights reserved.
00008 *
00009 * Redistribution and use in binary form, with or without modification,
00010 * is permitted provided that the following conditions are met:
00011 *
00012 *       * Redistributions in binary form must reproduce the above copyright
00013 *       notice, this list of conditions and the following disclaimer in the
00014 *       documentation and/or other materials provided with the distribution.
00015 *       * Neither the name of the Yaskawa America, Inc., nor the names 
00016 *       of its contributors may be used to endorse or promote products derived
00017 *       from this software without specific prior written permission.
00018 *
00019 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029 * POSSIBILITY OF SUCH DAMAGE.
00030 */ 
00031 
00032 #ifndef _INC_GETMOTOMANPARAMETERS_H
00033 #define _INC_GETMOTOMANPARAMETERS_H
00034 
00035 #ifdef __cplusplus
00036 extern "C" {
00037 #endif
00038 
00039 #define MAX_PARAM_BUFF 4000 //4k
00040 #define TAG_BUFF_LEN 10
00041 
00042 typedef struct
00043 {
00044         float PtoR[MAX_PULSE_AXES]; //Array to store PULSE TO RADIAN conversion factors for each axes
00045 }GB_PULSE_TO_RAD;
00046 
00047 typedef struct
00048 {
00049         BOOL  bValid;                   //TRUE if ulSourceAxis != 0
00050         INT32 ulSourceAxis;             
00051         INT32 ulCorrectionAxis;  
00052         float fCorrectionRatio; 
00053 } FB_AXIS_CORRECTION;
00054 
00055 typedef struct
00056 {
00057         FB_AXIS_CORRECTION  correction[MAX_PULSE_AXES];
00058 } FB_PULSE_CORRECTION_DATA;
00059 
00060 typedef struct
00061 {
00062         UINT32  qtyOfOutFiles;                          
00063         UINT32  qtyOfHighPriorityTasks;         
00064         UINT32  qtyOfNormalPriorityTasks;       
00065 } TASK_QTY_INFO;
00066         
00067 typedef struct
00068 {
00069         UINT16 periodInMilliseconds;
00070 } GP_INTERPOLATION_PERIOD;
00071 
00072 typedef struct
00073 {
00074         UINT32  maxIncrement[MAX_PULSE_AXES];
00075 } MAX_INCREMENT_INFO;
00076 
00077 typedef struct
00078 {
00079         int ctrlGrp;                            //Robot control group
00080         int IpCycleInMilliseconds;      //Interpolation Cycle in milliseconds
00081         MAX_INCREMENT_INFO info;        //Maximum increment per interpolation cycle
00082 } MAX_INC_PIPC;
00083         
00084 /******************************************************************************/
00085 /* << 2 >>                                                                        */
00086 /* Function name : int  GP_getNumberOfGroups()                                                            */
00087 /* Functionality : Retrieves the Number of Defined Groups                                         */
00088 /* Parameter     : NONE                                                                                                           */
00089 /* Return value  : Success = Number of Groups                                                             */
00090 /*                               : Failure = -1                                                                                           */    
00091 /******************************************************************************/
00092 extern int      GP_getNumberOfGroups();
00093 
00094 /******************************************************************************/
00095 /* << 3 >>                                                                        */
00096 /* Function name : int  GP_getNumberOfAxes()                                                              */
00097 /* Functionality : Retrieves the Number of Axes                                                           */
00098 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00099 /* Return value  : Success = Number of Axes                                                                       */
00100 /*                               : Failure = -1                                                                                           */    
00101 /******************************************************************************/
00102 extern int      GP_getNumberOfAxes(int ctrlGrp);
00103 
00104 /******************************************************************************/
00105 /* << 4 >>                                                                        */
00106 /* Function name : STATUS GP_getPulseToRad()                                                              */
00107 /* Functionality : Gets the Pulse to radians conversion factors                           */
00108 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00109 /*                                 GB_PULSE_TO_RAD *PulseToRad -array of conversion data [OUT]*/
00110 /* Return value  : Success = OK                                                                                           */
00111 /*                               : Failure = NG                                                                                           */    
00112 /******************************************************************************/
00113 extern STATUS   GP_getPulseToRad(int ctrlGrp, GB_PULSE_TO_RAD *PulseToRad);
00114         
00115 /******************************************************************************/
00116 /* << 11 >>                                                                       */
00117 /* Function name : STATUS GetFBPulseCorrection()                                                          */
00118 /* Functionality : Get all the pulse correction data for required axes            */
00119 /* Parameter     : int ctrlGrp - Robot control to fetch data [IN]                         */
00120 /*                                 FB_PULSE_CORRECTION_DATA * correctionData[OUT]                         */
00121 /* Return value  : Success = OK                                                                                           */
00122 /*                               : Failure = NG                                                                                           */
00123 /******************************************************************************/
00124 extern STATUS GP_getFBPulseCorrection(int ctrlGrp, FB_PULSE_CORRECTION_DATA *correctionData);
00125         
00126 /******************************************************************************/
00127 /* << 12 >>                                                                       */
00128 /* Function name : STATUS GP_getQtyOfAllowedTasks()                                                       */
00129 /* Functionality : No.of MotoPlus tasks that can be started concurrently          */
00130 /* Parameter     : TASK_QTY_INFO *taskInfo [OUT]                                                          */
00131 /* Return value  : Success = OK                                                                                           */
00132 /*                               : Failure = NG                                                                                           */
00133 /******************************************************************************/
00134 extern STATUS GP_getQtyOfAllowedTasks(TASK_QTY_INFO *taskInfo);
00135 
00136 /******************************************************************************/
00137 /* << 13 >>                                                                       */
00138 /* Function name : STATUS GP_getInterpolationPeriod()                                             */
00139 /* Functionality : No.of millisecs b/w each tick of the interpolation-clock       */
00140 /* Parameter     : UINT16 *periodInMilliseconds [OUT]                                             */
00141 /* Return value  : Success = OK                                                                                           */
00142 /*                               : Failure = NG                                                                                           */    
00143 /******************************************************************************/
00144 extern STATUS GP_getInterpolationPeriod(UINT16* periodInMilliseconds);
00145 
00146 /******************************************************************************/
00147 /* << 14 >>                                                                       */
00148 /* Function name : STATUS GP_getMaxIncPerIpCycle()                                                        */
00149 /* Functionality : Max increment the arm is capable of(limited by governor)       */
00150 /* Parameter     : int ctrlGrp - Robot control to fetch data [IN]                         */
00151 /*                                 int interpolationPeriodInMilliseconds - obtained from GP_getInterpolationPeriod [IN] */
00152 /*                                 MAX_INCREMENT_INFO *mip [OUT]                                                          */
00153 /* Return value  : Success = OK                                                                                           */
00154 /*                               : Failure = NG                                                                                           */    
00155 /******************************************************************************/
00156 extern STATUS GP_getMaxIncPerIpCycle(int ctrlGrp, int interpolationPeriodInMilliseconds, MAX_INCREMENT_INFO *mip);
00157 
00158 /******************************************************************************/
00159 /* << 15 >>                                                                       */
00160 /* Function name : GP_getGovForIncMotion()                                                                        */
00161 /* Functionality : Percentage Limit of the max-increment                                          */
00162 /* Parameter     : int ctrlGrp                          [IN]                                                      */
00163 /* Return value  : Success = percentage limit Of MaxSpeed                                         */
00164 /*                               : Failure = -1                                                                                           */    
00165 /******************************************************************************/
00166 extern float GP_getGovForIncMotion(int ctrlGrp);
00167 
00168 #ifdef __cplusplus
00169 }
00170 #endif
00171 
00172 #endif


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Wed Aug 26 2015 12:37:33