CtrlGroup.c
Go to the documentation of this file.
00001 // CtrlGroup.c
00002 //
00003 /*
00004 * Software License Agreement (BSD License) 
00005 *
00006 * Copyright (c) 2013, 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 #include "MotoROS.h"
00033 
00034 //-----------------------
00035 // Function implementation
00036 //-----------------------
00037 
00038 //-------------------------------------------------------------------
00039 // Search through the control group to find the GroupId that matches 
00040 // the group number
00041 //-------------------------------------------------------------------
00042 MP_GRP_ID_TYPE Ros_CtrlGroup_FindGrpId(int groupNo)
00043 {
00044         MP_GRP_ID_TYPE grp_id;
00045         
00046         for(grp_id = MP_R1_GID; grp_id < MP_S3_GID; grp_id++)
00047         {
00048                 if(groupNo == mpCtrlGrpId2GrpNo(grp_id))
00049                         return grp_id;
00050         }
00051         
00052         return -1;
00053 }
00054 
00055 //-------------------------------------------------------------------
00056 // Create a CtrlGroup data structure for existing group otherwise 
00057 // return NULL
00058 //-------------------------------------------------------------------
00059 CtrlGroup* Ros_CtrlGroup_Create(int groupNo, BOOL bIsLastGrpToInit, float interpolPeriod)
00060 {
00061         CtrlGroup* ctrlGroup;
00062         int numAxes;
00063         int i;
00064 #ifdef DX100            
00065         float speedCap;
00066 #endif
00067         long maxSpeedPulse[MP_GRP_AXES_NUM];
00068         STATUS status;
00069         BOOL bInitOk;
00070         BOOL slaveAxis;
00071         
00072         // Check if group is defined
00073         numAxes = GP_getNumberOfAxes(groupNo);
00074 #ifdef DEBUG
00075         printf("Group %d: Num Axes %d\n", groupNo, numAxes);
00076 #endif
00077         if(numAxes > 0)
00078         {
00079                 bInitOk = TRUE;
00080                 // Allocate and initialize memory
00081                 ctrlGroup = mpMalloc(sizeof(CtrlGroup));
00082                 memset(ctrlGroup, 0x00, sizeof(CtrlGroup));
00083                 
00084                 // Populate values
00085                 ctrlGroup->groupNo = groupNo;
00086                 ctrlGroup->numAxes = numAxes;
00087                 ctrlGroup->groupId = Ros_CtrlGroup_FindGrpId(groupNo);
00088 
00089                 status = GP_getAxisMotionType(groupNo, &ctrlGroup->axisType);
00090                 if (status != OK)
00091                         bInitOk = FALSE;
00092 
00093                 status = GP_getPulseToRad(groupNo, &ctrlGroup->pulseToRad);
00094                 if (status != OK)
00095                         bInitOk = FALSE;
00096 
00097                 status = GP_getPulseToMeter(groupNo, &ctrlGroup->pulseToMeter);
00098                 if (status != OK)
00099                         bInitOk = FALSE;
00100 
00101                 status = GP_getFBPulseCorrection(groupNo, &ctrlGroup->correctionData);
00102                 if(status!=OK)
00103                         bInitOk = FALSE;
00104 
00105                 status = GP_getMaxIncPerIpCycle(groupNo, interpolPeriod, &ctrlGroup->maxInc);
00106                 if (status != OK)
00107                         bInitOk = FALSE;
00108 
00109                 status = GP_isBaxisSlave(groupNo, &slaveAxis);
00110                 if (status != OK)
00111                         bInitOk = FALSE;
00112 
00113                 status = GP_getFeedbackSpeedMRegisterAddresses(groupNo, //zero based index of the control group
00114                                                                                                                 TRUE, //If the register-speed-feedback is not enabled, automatically modify the SC.PRM file to enable this feature.
00115                                                                                                                 bIsLastGrpToInit, //If activating the reg-speed-feedback feature, delay the alarm until all the groups have been processed.
00116                                                                                                                 &ctrlGroup->speedFeedbackRegisterAddress); //[OUT] Index of the M registers containing the feedback speed values.
00117                 if (status != OK)
00118                 {
00119                         ctrlGroup->speedFeedbackRegisterAddress.bFeedbackSpeedEnabled = FALSE;
00120                 }
00121 
00122                 ctrlGroup->bIsBaxisSlave = (numAxes == 5) && slaveAxis;
00123 
00124                 //adjust the axisType field to account for robots with non-contiguous axes (such as delta or palletizing which use SLU--T axes)
00125                 for (i = 0; i < MP_GRP_AXES_NUM; i += 1)
00126                 {
00127                         if (ctrlGroup->maxInc.maxIncrement[i] == 0) //if the axis can't move, then I assume it's invalid
00128                                 ctrlGroup->axisType.type[i] = AXIS_INVALID;
00129                 }
00130 
00131                 memset(&ctrlGroup->inc_q, 0x00, sizeof(Incremental_q));
00132                 ctrlGroup->inc_q.q_lock = mpSemBCreate(SEM_Q_FIFO, SEM_FULL);
00133 
00134 #ifdef DX100            
00135                 speedCap = GP_getGovForIncMotion(groupNo);
00136                 if(speedCap != -1)
00137                 {
00138                         for(i=0; i<MP_GRP_AXES_NUM; i++)
00139                                 ctrlGroup->maxInc.maxIncrement[i] *= speedCap;
00140                 }
00141                 else
00142                         bInitOk = FALSE;
00143 #endif
00144 
00145                 // Calculate maximum speed in radian per second
00146                 memset(maxSpeedPulse, 0x00, sizeof(maxSpeedPulse));
00147                 for(i=0; i<MP_GRP_AXES_NUM; i++)
00148                         maxSpeedPulse[i] = ctrlGroup->maxInc.maxIncrement[i] * 1000.0 / interpolPeriod; 
00149                 Ros_CtrlGroup_ConvertToRosPos(ctrlGroup, maxSpeedPulse, ctrlGroup->maxSpeed); 
00150 
00151                 printf("axisType[%d]: ", groupNo);
00152                 for (i = 0; i < MP_GRP_AXES_NUM; i++)
00153                 {
00154                         if (ctrlGroup->axisType.type[i] == AXIS_LINEAR)
00155                                 printf("Lin\t");
00156                         else if (ctrlGroup->axisType.type[i] == AXIS_ROTATION)
00157                                 printf("Rot\t");
00158                         else
00159                         {
00160                                 printf("---\t");
00161                                 //motoRosAssert(FALSE, SUBCODE_INVALID_AXIS_TYPE, "Grp%d Axs%d type invalid", groupNo, i);
00162                         }
00163                 }
00164                 printf(";\r\n");
00165 
00166                 printf("pulse->unit[%d]: ", groupNo);
00167                 for (i = 0; i < MP_GRP_AXES_NUM; i++)
00168                 {
00169                         if (ctrlGroup->axisType.type[i] == AXIS_LINEAR)
00170                                 printf("%.4f\t", ctrlGroup->pulseToMeter.PtoM[i]);
00171                         else if (ctrlGroup->axisType.type[i] == AXIS_ROTATION)
00172                                 printf("%.4f\t", ctrlGroup->pulseToRad.PtoR[i]);
00173                         else
00174                                 printf("--\t");
00175                 }
00176                 printf(";\r\n");
00177 
00178                 printf("maxInc[%d] (in motoman joint order): %d, %d, %d, %d, %d, %d, %d\r\n", 
00179                         groupNo,
00180                         ctrlGroup->maxInc.maxIncrement[0],ctrlGroup->maxInc.maxIncrement[1],ctrlGroup->maxInc.maxIncrement[2],
00181                         ctrlGroup->maxInc.maxIncrement[3],ctrlGroup->maxInc.maxIncrement[4],ctrlGroup->maxInc.maxIncrement[5],
00182                         ctrlGroup->maxInc.maxIncrement[6]);
00183 
00184                 printf("maxSpeed[%d] (in ros joint order): %.6f, %.6f, %.6f, %.6f, %.6f, %.6f, %.6f\r\n",
00185                         groupNo,
00186                         ctrlGroup->maxSpeed[0],ctrlGroup->maxSpeed[1],ctrlGroup->maxSpeed[2],
00187                         ctrlGroup->maxSpeed[3],ctrlGroup->maxSpeed[4],ctrlGroup->maxSpeed[5],
00188                         ctrlGroup->maxSpeed[6]);
00189 
00190                 ctrlGroup->tidAddToIncQueue = INVALID_TASK;
00191                 
00192                 if(bInitOk == FALSE)
00193                 {
00194                         mpFree(ctrlGroup);
00195                         ctrlGroup = NULL;
00196                 }
00197         }
00198         else
00199         {
00200                 ctrlGroup = NULL;
00201         }
00202         
00203         return ctrlGroup;
00204 }
00205 
00206 
00207 //-------------------------------------------------------------------
00208 // Get the commanded pulse position in pulse (in motoman joint order)
00209 // Used for MOTION SERVER connection for positional planning calculations.
00210 //-------------------------------------------------------------------
00211 BOOL Ros_CtrlGroup_GetPulsePosCmd(CtrlGroup* ctrlGroup, long pulsePos[MAX_PULSE_AXES])
00212 {
00213         LONG status = 0;
00214         MP_CTRL_GRP_SEND_DATA sData;
00215         MP_PULSE_POS_RSP_DATA pulse_data;
00216         float rosAnglePos[MP_GRP_AXES_NUM]; //temporary storage for B axis compensation
00217         int i;
00218 
00219         memset(pulsePos, 0, MAX_PULSE_AXES*sizeof(long));  // clear result, in case of error
00220 
00221         // Set the control group
00222         switch(ctrlGroup->groupId)
00223         {
00224                 case MP_R1_GID: sData.sCtrlGrp = 0; break;
00225                 case MP_R2_GID: sData.sCtrlGrp = 1; break;
00226                 case MP_R3_GID: sData.sCtrlGrp = 2; break;
00227                 case MP_R4_GID: sData.sCtrlGrp = 3; break;
00228                 case MP_B1_GID: sData.sCtrlGrp = 8; break;
00229                 case MP_B2_GID: sData.sCtrlGrp = 9; break;
00230                 case MP_B3_GID: sData.sCtrlGrp = 10; break;
00231                 case MP_B4_GID: sData.sCtrlGrp = 11; break;
00232                 case MP_S1_GID: sData.sCtrlGrp = 16; break;
00233                 case MP_S2_GID: sData.sCtrlGrp = 17; break;
00234                 case MP_S3_GID: sData.sCtrlGrp = 18; break;
00235                 default:
00236                         printf("Failed to get pulse feedback position\nInvalid groupId: %d\n", ctrlGroup->groupId);
00237                         return FALSE;
00238         }
00239         
00240         // get the command joint positions
00241         status = mpGetPulsePos (&sData,&pulse_data);
00242         if (0 != status)
00243         {
00244                 printf("Failed to get pulse position (command): %u\n", status);
00245                 return FALSE;
00246         }
00247         
00248         // assign return value
00249         for (i=0; i<MAX_PULSE_AXES; ++i)
00250                 pulsePos[i] = pulse_data.lPos[i];
00251 
00252         // For MPL80/100 robot type (SLUBT): Controller automatically moves the B-axis
00253         // to maintain orientation as other axes are moved.
00254         if (ctrlGroup->bIsBaxisSlave)
00255         {
00256                 //B axis compensation works on the ROS ANGLE positions, not on MOTO PULSE positions
00257                 Ros_CtrlGroup_ConvertToRosPos(ctrlGroup, pulsePos, rosAnglePos);
00258                 rosAnglePos[3] += -rosAnglePos[1] + rosAnglePos[2];
00259                 Ros_CtrlGroup_ConvertToMotoPos(ctrlGroup, rosAnglePos, pulsePos);
00260         }
00261 
00262         return TRUE;
00263 }
00264 
00265 
00266 //-------------------------------------------------------------------
00267 // Get the corrected feedback pulse position in pulse.
00268 // Used exclusively for STATE SERVER connection to report position.
00269 //-------------------------------------------------------------------
00270 BOOL Ros_CtrlGroup_GetFBPulsePos(CtrlGroup* ctrlGroup, long pulsePos[MAX_PULSE_AXES])
00271 {
00272         LONG status = 0;
00273         MP_CTRL_GRP_SEND_DATA sData;
00274 #ifndef DUMMY_SERVO_MODE
00275         MP_FB_PULSE_POS_RSP_DATA pulse_data;
00276 #else
00277         MP_PULSE_POS_RSP_DATA pulse_data;
00278 #endif
00279         int i;
00280 
00281         memset(pulsePos, 0, MAX_PULSE_AXES*sizeof(long));  // clear result, in case of error
00282 
00283         // Set the control group
00284         switch(ctrlGroup->groupId)
00285         {
00286                 case MP_R1_GID: sData.sCtrlGrp = 0; break;
00287                 case MP_R2_GID: sData.sCtrlGrp = 1; break;
00288                 case MP_R3_GID: sData.sCtrlGrp = 2; break;
00289                 case MP_R4_GID: sData.sCtrlGrp = 3; break;
00290                 case MP_B1_GID: sData.sCtrlGrp = 8; break;
00291                 case MP_B2_GID: sData.sCtrlGrp = 9; break;
00292                 case MP_B3_GID: sData.sCtrlGrp = 10; break;
00293                 case MP_B4_GID: sData.sCtrlGrp = 11; break;
00294                 case MP_S1_GID: sData.sCtrlGrp = 16; break;
00295                 case MP_S2_GID: sData.sCtrlGrp = 17; break;
00296                 case MP_S3_GID: sData.sCtrlGrp = 18; break;
00297                 default: 
00298                         printf("Failed to get pulse feedback position\nInvalid groupId: %d\n", ctrlGroup->groupId);
00299                         return FALSE;
00300         }
00301         
00302 #ifndef DUMMY_SERVO_MODE
00303         // get raw (uncorrected/unscaled) joint positions
00304         status = mpGetFBPulsePos (&sData,&pulse_data);
00305         if (0 != status)
00306         {
00307                 printf("Failed to get pulse feedback position: %u\n", status);
00308                 return FALSE;
00309         }
00310         
00311         // apply correction to account for cross-axis coupling
00312         // Note: this is only required for feedback position
00313         // controller handles this correction internally when 
00314         // dealing with command positon.
00315         for (i=0; i<MAX_PULSE_AXES; ++i)
00316         {
00317                 FB_AXIS_CORRECTION *corr = &ctrlGroup->correctionData.correction[i];
00318                 if (corr->bValid)
00319                 {
00320                         int src_axis = corr->ulSourceAxis;
00321                         int dest_axis = corr->ulCorrectionAxis;
00322                         pulse_data.lPos[dest_axis] -= (int)(pulse_data.lPos[src_axis] * corr->fCorrectionRatio);
00323                 }
00324         }
00325 #else
00326         mpGetPulsePos(&sData, &pulse_data);
00327 #endif
00328         
00329         // assign return value
00330         for (i=0; i<MAX_PULSE_AXES; ++i)
00331                 pulsePos[i] = pulse_data.lPos[i];
00332 
00333         //--------------------------------------------------------------------
00334         //NOTE: Do NOT apply any B axis compensation here. 
00335         //              This is actual feedback which is reported to the state server.
00336         //--------------------------------------------------------------------
00337         
00338         return TRUE;
00339 }
00340 
00341 //-------------------------------------------------------------------
00342 // Get the corrected feedback pulse speed in pulse for each axis.
00343 //-------------------------------------------------------------------
00344 BOOL Ros_CtrlGroup_GetFBServoSpeed(CtrlGroup* ctrlGroup, long pulseSpeed[MAX_PULSE_AXES])
00345 {
00346         int i;
00347 
00348 #ifndef DUMMY_SERVO_MODE
00349         LONG status;
00350         MP_IO_INFO registerInfo[MAX_PULSE_AXES * 2]; //values are 4 bytes, which consumes 2 registers
00351         USHORT registerValues[MAX_PULSE_AXES * 2];
00352         UINT32 registerValuesLong[MAX_PULSE_AXES * 2];
00353         double dblRegister;
00354 
00355         if (!ctrlGroup->speedFeedbackRegisterAddress.bFeedbackSpeedEnabled)
00356                 return FALSE;
00357 
00358         for (i = 0; i < MAX_PULSE_AXES; i += 1)
00359         {
00360                 registerInfo[i * 2].ulAddr = ctrlGroup->speedFeedbackRegisterAddress.cioAddressForAxis[i][0];
00361                 registerInfo[(i * 2) + 1].ulAddr = ctrlGroup->speedFeedbackRegisterAddress.cioAddressForAxis[i][1];
00362         }
00363 
00364         // get raw (uncorrected/unscaled) joint speeds
00365         status = mpReadIO(registerInfo, registerValues, MAX_PULSE_AXES * 2);
00366         if (status != OK)
00367         {
00368                 printf("Failed to get pulse feedback speed: %u\n", status);
00369                 return FALSE;
00370         }
00371 
00372         for (i = 0; i < MAX_PULSE_AXES; i += 1)
00373         {
00374                 //move to 32 bit storage
00375                 registerValuesLong[i * 2] = registerValues[i * 2];
00376                 registerValuesLong[(i * 2) + 1] = registerValues[(i * 2) + 1];
00377 
00378                 //combine both registers into single 4 byte value (0.0001 deg/sec or 1 um/sec)
00379                 dblRegister = (registerValuesLong[(i * 2) + 1] << 16) | registerValuesLong[i * 2];
00380 
00381                 //convert to pulse/sec
00382                 if (ctrlGroup->axisType.type[i] == AXIS_ROTATION)
00383                 {
00384                         dblRegister /= 1.0E4; //deg/sec
00385                         dblRegister *= RAD_PER_DEGREE; //rad/sec
00386                         dblRegister *= ctrlGroup->pulseToRad.PtoR[i]; //pulse/sec
00387                 }
00388                 else if (ctrlGroup->axisType.type[i] == AXIS_LINEAR)
00389                 {
00390                         dblRegister /= 1.0E6; //m/sec
00391                         dblRegister *= ctrlGroup->pulseToMeter.PtoM[i]; //pulse/sec
00392                 }
00393 
00394                 pulseSpeed[i] = (long)dblRegister;
00395         }
00396 
00397         // Apply correction to account for cross-axis coupling.
00398         // Note: This is only required for feedback.
00399         // Controller handles this correction internally when 
00400         // dealing with command positon.
00401         for (i = 0; i<MAX_PULSE_AXES; ++i)
00402         {
00403                 FB_AXIS_CORRECTION *corr = &ctrlGroup->correctionData.correction[i];
00404                 if (corr->bValid)
00405                 {
00406                         int src_axis = corr->ulSourceAxis;
00407                         int dest_axis = corr->ulCorrectionAxis;
00408                         pulseSpeed[dest_axis] -= (int)(pulseSpeed[src_axis] * corr->fCorrectionRatio);
00409                 }
00410         }
00411 #else
00412         MP_CTRL_GRP_SEND_DATA sData;
00413         MP_SERVO_SPEED_RSP_DATA pulse_data;
00414 
00415         mpGetServoSpeed(&sData, &pulse_data);
00416 
00417         // assign return value
00418         for (i = 0; i<MAX_PULSE_AXES; ++i)
00419                 pulseSpeed[i] = pulse_data.lSpeed[i];
00420 #endif
00421 
00422         return TRUE;
00423 }
00424 
00425 //-------------------------------------------------------------------
00426 // Retrieves the absolute value (Nm) of the maximum current servo torque.
00427 //-------------------------------------------------------------------
00428 BOOL Ros_CtrlGroup_GetTorque(CtrlGroup* ctrlGroup, double torqueValues[MAX_PULSE_AXES])
00429 {
00430     MP_GRP_AXES_T dst_vel;
00431     MP_TRQ_CTL_VAL dst_trq;
00432         LONG status = 0;
00433         int i;
00434 
00435         memset(torqueValues, 0, sizeof(torqueValues)); // clear result, in case of error
00436         memset(dst_trq.data, 0, sizeof(MP_TRQCTL_DATA));
00437         dst_trq.unit = TRQ_NEWTON_METER; //request data in Nm
00438 
00439         status = mpSvsGetVelTrqFb(dst_vel, &dst_trq);
00440         if (status != OK)
00441                 return FALSE;
00442 
00443         for (i = 0; i < MAX_PULSE_AXES; i += 1) 
00444         {
00445             torqueValues[i] = (double)dst_trq.data[ctrlGroup->groupId][i] * 0.000001; //Use double.  Float only good for 6 sig digits.
00446         }
00447     
00448     return TRUE;
00449 }
00450 
00451 // Convert Motoman position in pulse to Ros position in radian/meters
00452 // In the case of a 7, 4, or 5 axis robot, adjust the order to match 
00453 // the physical axis sequence
00454 //-------------------------------------------------------------------
00455 void Ros_CtrlGroup_ConvertToRosPos(CtrlGroup* ctrlGroup, long motopulsePos[MAX_PULSE_AXES],
00456                                                                         float rosPos[MAX_PULSE_AXES])
00457 {
00458         int i;
00459         float conversion = 1;
00460         int rpi = 0; //rosPos index
00461         int mpi = 0; //motopos index
00462 
00463         if ((ctrlGroup->numAxes == 7) && Ros_CtrlGroup_IsRobot(ctrlGroup)) //is robot, and is 7 axis
00464         {
00465                 // Adjust joint order for 7 axis robot (SLURBTE > SLEURBT); All rotary axes
00466 
00467                 for (i = 0; i < ctrlGroup->numAxes; i++)
00468                 {
00469                         if (i < 2)
00470                                 rosPos[i] = motopulsePos[i] / ctrlGroup->pulseToRad.PtoR[i];
00471                         else if (i == 2)
00472                                 rosPos[2] = motopulsePos[6] / ctrlGroup->pulseToRad.PtoR[6];
00473                         else
00474                                 rosPos[i] = motopulsePos[i - 1] / ctrlGroup->pulseToRad.PtoR[i - 1];
00475                 }
00476         }
00477         else if (Ros_CtrlGroup_IsRobot(ctrlGroup) && ctrlGroup->numAxes < 6)
00478         {
00479                 //Delta: (SLU--T- > SLUT---) All rotary axes
00480                 //Scara: (SLUR--- > SLUR---) U-axis is linear
00481                 //Large Palletizing: (SLU--T- > SLUT---) All rotary axes
00482                 //High Speed Picking: (SLU-BT- > SLUBT--) All rotary axes
00483 
00484                 for (i = rpi = mpi = 0; i < ctrlGroup->numAxes; i += 1, rpi += 1, mpi += 1)
00485                 {
00486                         while (ctrlGroup->axisType.type[mpi] == AXIS_INVALID)
00487                         {
00488                                 mpi += 1;
00489                                 if (mpi >= MAX_PULSE_AXES)
00490                                         return;
00491                         }
00492 
00493                         if (ctrlGroup->axisType.type[mpi] == AXIS_ROTATION)
00494                                 conversion = ctrlGroup->pulseToRad.PtoR[mpi];
00495                         else if (ctrlGroup->axisType.type[mpi] == AXIS_LINEAR)
00496                                 conversion = ctrlGroup->pulseToMeter.PtoM[mpi];
00497                         else
00498                                 conversion = 1.0;
00499 
00500                         rosPos[rpi] = motopulsePos[mpi] / conversion;
00501                 }
00502         }
00503         else
00504         {
00505                 for (i = 0; i < MAX_PULSE_AXES; i++)
00506                 {
00507                         if (ctrlGroup->axisType.type[i] == AXIS_ROTATION)
00508                                 conversion = ctrlGroup->pulseToRad.PtoR[i];
00509                         else if (ctrlGroup->axisType.type[i] == AXIS_LINEAR)
00510                                 conversion = ctrlGroup->pulseToMeter.PtoM[i];
00511                         else
00512                                 conversion = 1.0;
00513 
00514                         rosPos[i] = motopulsePos[i] / conversion;
00515                 }
00516         }
00517 }
00518 
00519 //-------------------------------------------------------------------
00520 // Convert Ros position in radian to Motoman position in pulse
00521 // In the case of a 7 or 4 axis robot, adjust the order to match 
00522 // the motoman axis sequence
00523 //-------------------------------------------------------------------
00524 void Ros_CtrlGroup_ConvertToMotoPos(CtrlGroup* ctrlGroup, float radPos[MAX_PULSE_AXES], long motopulsePos[MAX_PULSE_AXES])
00525 {
00526         int i;
00527         float conversion = 1;
00528         int rpi = 0; //radpos index
00529         int mpi = 0; //motopos index
00530 
00531         // Initialize memory space
00532         memset(motopulsePos, 0x00, sizeof(long)*MAX_PULSE_AXES);
00533 
00534         if ((ctrlGroup->numAxes == 7) && Ros_CtrlGroup_IsRobot(ctrlGroup))
00535         {
00536                 // Adjust joint order for 7 axis robot (SLEURBT > SLURBTE); All rotary axes
00537 
00538                 for (i = 0; i < ctrlGroup->numAxes; i++)
00539                 {
00540                         if (i < 2)
00541                                 motopulsePos[i] = (int)(radPos[i] * ctrlGroup->pulseToRad.PtoR[i]);
00542                         else if (i == 2)
00543                                 motopulsePos[6] = (int)(radPos[2] * ctrlGroup->pulseToRad.PtoR[6]);
00544                         else
00545                                 motopulsePos[i - 1] = (int)(radPos[i] * ctrlGroup->pulseToRad.PtoR[i - 1]);
00546                 }
00547         }
00548         else if (Ros_CtrlGroup_IsRobot(ctrlGroup) && ctrlGroup->numAxes < 6)
00549         {
00550                 //Delta: (SLUT--- > SLU--T-) All rotary axes
00551                 //Scara: (SLUR--- > SLUR---) U-axis is linear
00552                 //Large Palletizing: (SLUT--- > SLU--T-) All rotary axes
00553                 //High Speed Picking: (SLUBT-- > SLU-BT-) All rotary axes
00554 
00555                 for (i = rpi = mpi = 0; i < ctrlGroup->numAxes; i += 1, rpi += 1, mpi += 1)
00556                 {
00557                         while (ctrlGroup->axisType.type[mpi] == AXIS_INVALID)
00558                         {
00559                                 mpi += 1;
00560                                 if (mpi >= MAX_PULSE_AXES)
00561                                         return;
00562                         }
00563 
00564                         if (ctrlGroup->axisType.type[mpi] == AXIS_ROTATION)
00565                                 conversion = ctrlGroup->pulseToRad.PtoR[mpi];
00566                         else if (ctrlGroup->axisType.type[mpi] == AXIS_LINEAR)
00567                                 conversion = ctrlGroup->pulseToMeter.PtoM[mpi];
00568                         else
00569                                 conversion = 1.0;
00570 
00571                         motopulsePos[mpi] = (int)(radPos[rpi] * conversion);
00572                 }
00573         }
00574         else
00575         {
00576                 // Convert to pulse
00577                 for (i = 0; i < MAX_PULSE_AXES; i++)
00578                 {
00579                         if (ctrlGroup->axisType.type[i] == AXIS_ROTATION)
00580                                 conversion = ctrlGroup->pulseToRad.PtoR[i];
00581                         else if (ctrlGroup->axisType.type[i] == AXIS_LINEAR)
00582                                 conversion = ctrlGroup->pulseToMeter.PtoM[i];
00583                         else
00584                                 conversion = 1.0;
00585 
00586                         motopulsePos[i] = (int)(radPos[i] * conversion);
00587                 }
00588         }
00589 }
00590 
00591 //-------------------------------------------------------------------
00592 // Returns a bit wise axis configuration for the increment move API
00593 //-------------------------------------------------------------------
00594 UCHAR Ros_CtrlGroup_GetAxisConfig(CtrlGroup* ctrlGroup)
00595 {
00596         int i;
00597         int axisConfig = 0;
00598         
00599         for (i = 0; i < MAX_PULSE_AXES; i++)
00600         {
00601                 if (ctrlGroup->axisType.type[i] != AXIS_INVALID)
00602                         axisConfig |= (0x01 << i);
00603         }
00604                 
00605         return (UCHAR)axisConfig;
00606 }
00607 
00608 //-------------------------------------------------------------------
00609 // Returns TRUE is the specified group is defined as a robot
00610 //-------------------------------------------------------------------
00611 BOOL Ros_CtrlGroup_IsRobot(CtrlGroup* ctrlGroup)
00612 {
00613         return((ctrlGroup->groupId >= MP_R1_GID) && (ctrlGroup->groupId <= MP_R4_GID));
00614 }


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