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 #include "ParameterTypes.h"
00036 
00037 #ifdef __cplusplus
00038 extern "C" {
00039 #endif
00040 
00041 /******************************************************************************/
00042 /* << 2 >>                                                                        */
00043 /* Function name : int  GP_getNumberOfGroups()                                                            */
00044 /* Functionality : Retrieves the Number of Defined Groups                                         */
00045 /* Parameter     : NONE                                                                                                           */
00046 /* Return value  : Success = Number of Groups                                                             */
00047 /*                               : Failure = -1                                                                                           */    
00048 /******************************************************************************/
00049 extern int      GP_getNumberOfGroups();
00050 
00051 /******************************************************************************/
00052 /* << 3 >>                                                                        */
00053 /* Function name : int  GP_getNumberOfAxes()                                                              */
00054 /* Functionality : Retrieves the Number of Axes                                                           */
00055 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00056 /* Return value  : Success = Number of Axes                                                                       */
00057 /*                               : Failure = -1                                                                                           */    
00058 /******************************************************************************/
00059 extern int      GP_getNumberOfAxes(int ctrlGrp);
00060 
00061 /******************************************************************************/
00062 /* << 4 >>                                                                        */
00063 /* Function name : STATUS GP_getPulseToRad()                                                              */
00064 /* Functionality : Gets the Pulse to radians conversion factors                           */
00065 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00066 /*                                 GB_PULSE_TO_RAD *PulseToRad -array of conversion data [OUT]*/
00067 /* Return value  : Success = OK                                                                                           */
00068 /*                               : Failure = NG                                                                                           */    
00069 /******************************************************************************/
00070 extern STATUS   GP_getPulseToRad(int ctrlGrp, PULSE_TO_RAD *PulseToRad);
00071 
00072 /******************************************************************************/
00073 /* << 11 >>                                                                       */
00074 /* Function name : STATUS GetFBPulseCorrection()                                                          */
00075 /* Functionality : Get all the pulse correction data for required axes            */
00076 /* Parameter     : int ctrlGrp - Robot control to fetch data [IN]                         */
00077 /*                                 FB_PULSE_CORRECTION_DATA * correctionData[OUT]                         */
00078 /* Return value  : Success = OK                                                                                           */
00079 /*                               : Failure = NG                                                                                           */
00080 /******************************************************************************/
00081 extern STATUS GP_getFBPulseCorrection(int ctrlGrp, FB_PULSE_CORRECTION_DATA *correctionData);
00082         
00083 /******************************************************************************/
00084 /* << 12 >>                                                                       */
00085 /* Function name : STATUS GP_getQtyOfAllowedTasks()                                                       */
00086 /* Functionality : No.of MotoPlus tasks that can be started concurrently          */
00087 /* Parameter     : TASK_QTY_INFO *taskInfo [OUT]                                                          */
00088 /* Return value  : Success = OK                                                                                           */
00089 /*                               : Failure = NG                                                                                           */
00090 /******************************************************************************/
00091 extern STATUS GP_getQtyOfAllowedTasks(TASK_QTY_INFO *taskInfo);
00092 
00093 /******************************************************************************/
00094 /* << 13 >>                                                                       */
00095 /* Function name : STATUS GP_getInterpolationPeriod()                                             */
00096 /* Functionality : No.of millisecs b/w each tick of the interpolation-clock       */
00097 /* Parameter     : UINT16 *periodInMilliseconds [OUT]                                             */
00098 /* Return value  : Success = OK                                                                                           */
00099 /*                               : Failure = NG                                                                                           */    
00100 /******************************************************************************/
00101 extern STATUS GP_getInterpolationPeriod(UINT16* periodInMilliseconds);
00102 
00103 /******************************************************************************/
00104 /* << 14 >>                                                                       */
00105 /* Function name : STATUS GP_getMaxIncPerIpCycle()                                                        */
00106 /* Functionality : Max increment the arm is capable of(limited by governor)       */
00107 /* Parameter     : int ctrlGrp - Robot control to fetch data [IN]                         */
00108 /*                                 int interpolationPeriodInMilliseconds - obtained from GP_getInterpolationPeriod [IN] */
00109 /*                                 MAX_INCREMENT_INFO *mip [OUT]                                                          */
00110 /* Return value  : Success = OK                                                                                           */
00111 /*                               : Failure = NG                                                                                           */    
00112 /******************************************************************************/
00113 extern STATUS GP_getMaxIncPerIpCycle(int ctrlGrp, int interpolationPeriodInMilliseconds, MAX_INCREMENT_INFO *mip);
00114 
00115 /******************************************************************************/
00116 /* << 15 >>                                                                       */
00117 /* Function name : GP_getGovForIncMotion()                                                                        */
00118 /* Functionality : Percentage Limit of the max-increment                                          */
00119 /* Parameter     : int ctrlGrp                          [IN]                                                      */
00120 /* Return value  : Success = percentage limit Of MaxSpeed                                         */
00121 /*                               : Failure = -1                                                                                           */    
00122 /******************************************************************************/
00123 extern float GP_getGovForIncMotion(int ctrlGrp);
00124 
00125 /******************************************************************************/
00126 /* << 16 >>                                                                       */
00127 /* Function name : STATUS GP_getJointPulseLimits()                                                        */
00128 /* Functionality : Gets the Pulse to radians conversion factors                           */
00129 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00130 /*                                 GB_PULSE_TO_RAD *PulseToRad -array of conversion data [OUT]*/
00131 /* Return value  : Success = OK                                                                                           */
00132 /*                               : Failure = NG                                                                                           */
00133 /******************************************************************************/
00134 extern STATUS GP_getJointPulseLimits(int ctrlGrp, JOINT_PULSE_LIMITS* jointPulseLimits);
00135 
00136 /******************************************************************************/
00137 /* << 17 >>                                                                       */
00138 /* Function name : STATUS GP_getJointVelocityLimits()                                             */
00139 /* Functionality : Gets the velocity limit for each joint                                         */
00140 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00141 /*                                 JOINT_ANGULAR_VELOCITY_LIMITS *GP_getJointAngularVelocityLimits (deg/sec) [OUT]*/
00142 /* Return value  : Success = OK                                                                                           */
00143 /*                               : Failure = NG                                                                                           */
00144 /******************************************************************************/
00145 extern STATUS GP_getJointAngularVelocityLimits(int ctrlGrp, JOINT_ANGULAR_VELOCITY_LIMITS* jointVelocityLimits);
00146 
00147 /******************************************************************************/
00148 /* << 18 >>                                                                       */
00149 /* Function name : STATUS GP_getAxisMotionType()                                                          */
00150 /* Functionality : Gets the motion type of each axis in the group                         */
00151 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00152 /*                                 AXIS_MOTION_TYPE *axisType -array of data [OUT]                        */
00153 /* Return value  : Success = OK                                                                                           */
00154 /*                               : Failure = NG                                                                                           */
00155 /******************************************************************************/
00156 extern STATUS   GP_getAxisMotionType(int ctrlGrp, AXIS_MOTION_TYPE* axisType);
00157 
00158 /******************************************************************************/
00159 /* << 19 >>                                                                       */
00160 /* Function name : STATUS GP_getPulseToMeter()                                                            */
00161 /* Functionality : Gets the Pulse to meter conversion factors                             */
00162 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00163 /*                                 PULSE_TO_METER *PulseToMeter -array of conversion data [OUT]*/
00164 /* Return value  : Success = OK                                                                                           */
00165 /*                               : Failure = NG                                                                                           */
00166 /******************************************************************************/
00167 extern STATUS   GP_getPulseToMeter(int ctrlGrp, PULSE_TO_METER* PulseToMeter);
00168 
00169 /******************************************************************************/
00170 /* << 20 >>                                                                       */
00171 /* Function name : STATUS GP_isBaxisSlave()                                                                       */
00172 /* Functionality : Determines if B axis is automatically moved relative to        */
00173 /*                                 other axes.                                                                                            */
00174 /* Parameter     : int ctrlGrp - Robot control to fetch data    [IN]              */
00175 /*                                 BOOL* bBaxisIsSlave - TRUE if b axis is slave [OUT]            */
00176 /* Return value  : Success = OK                                                                                           */
00177 /*                               : Failure = NG                                                                                           */
00178 /******************************************************************************/
00179 extern STATUS   GP_isBaxisSlave(int ctrlGrp, BOOL* bBaxisIsSlave);
00180 
00181 /******************************************************************************/
00182 /* << 21 >>                                                                       */
00183 /* Function name : STATUS GP_getFeedbackSpeedMRegisterAddresses()                         */
00184 /* Functionality : Obtains the MRegister CIO addresses that contain the           */
00185 /*                                 feedback speed for each axis. Optionally enables this      */
00186 /*                                 feature if not already enabled.                                                    */
00187 /* Parameter     : int ctrlGrp - Robot control group (zero based index) [IN]  */
00188 /*                                 BOOL bActivateIfNotEnabled - TRUE to enable feature [IN]   */
00189 /*                                 BOOL bForceRebootAfterActivation - TRUE to force the user  */
00190 /*                                 to reboot if this feature gets activated. Set to FALSE if  */
00191 /*                                 you plan to enable for additional control groups. [IN]     */
00192 /*                                 JOINT_FEEDBACK_SPEED_ADDRESSES* registerAddresses -            */
00193 /*                                 Obtains the CIO register address for the feedback data [OUT]*/
00194 /* Return value  : Success = OK                                                                                           */
00195 /*                               : Failure = NG                                                                                           */
00196 /******************************************************************************/
00197 extern STATUS   GP_getFeedbackSpeedMRegisterAddresses(int ctrlGrp, BOOL bActivateIfNotEnabled, BOOL bForceRebootAfterActivation, JOINT_FEEDBACK_SPEED_ADDRESSES* registerAddresses);
00198 
00199 #ifdef __cplusplus
00200 }
00201 #endif
00202 
00203 #endif


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute)
autogenerated on Sat Jun 8 2019 19:06:58