MotionServer.c
Go to the documentation of this file.
00001 // MotionServer.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 Declarations
00036 //-----------------------
00037 // Main Task: 
00038 void Ros_MotionServer_StartNewConnection(Controller* controller, int sd);
00039 void Ros_MotionServer_StopConnection(Controller* controller, int connectionIndex);
00040 
00041 // WaitForSimpleMsg Task:
00042 void Ros_MotionServer_WaitForSimpleMsg(Controller* controller, int connectionIndex);
00043 BOOL Ros_MotionServer_SimpleMsgProcess(Controller* controller, SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00044 int Ros_MotionServer_MotionCtrlProcess(Controller* controller, SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00045 BOOL Ros_MotionServer_StopMotion(Controller* controller);
00046 BOOL Ros_MotionServer_ServoPower(Controller* controller, int servoOnOff);
00047 BOOL Ros_MotionServer_ResetAlarm(Controller* controller);
00048 BOOL Ros_MotionServer_StartTrajMode(Controller* controller);
00049 BOOL Ros_MotionServer_StopTrajMode(Controller* controller);
00050 int Ros_MotionServer_JointTrajDataProcess(Controller* controller, SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00051 int Ros_MotionServer_InitTrajPointFull(CtrlGroup* ctrlGroup, SmBodyJointTrajPtFull* jointTrajData);
00052 int Ros_MotionServer_InitTrajPointFullEx(CtrlGroup* ctrlGroup, SmBodyJointTrajPtExData* jointTrajDataEx, int sequence);
00053 int Ros_MotionServer_AddTrajPointFull(CtrlGroup* ctrlGroup, SmBodyJointTrajPtFull* jointTrajData);
00054 int Ros_MotionServer_AddTrajPointFullEx(CtrlGroup* ctrlGroup, SmBodyJointTrajPtExData* jointTrajDataEx, int sequence);
00055 int Ros_MotionServer_JointTrajPtFullExProcess(Controller* controller, SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00056 
00057 // AddToIncQueue Task:
00058 void Ros_MotionServer_AddToIncQueueProcess(Controller* controller, int groupNo);
00059 void Ros_MotionServer_JointTrajDataToIncQueue(Controller* controller, int groupNo);
00060 BOOL Ros_MotionServer_AddPulseIncPointToQ(Controller* controller, int groupNo, Incremental_data* dataToEnQ);
00061 BOOL Ros_MotionServer_ClearQ_All(Controller* controller);
00062 BOOL Ros_MotionServer_HasDataInQueue(Controller* controller);
00063 int Ros_MotionServer_GetQueueCnt(Controller* controller, int groupNo);
00064 void Ros_MotionServer_IncMoveLoopStart(Controller* controller);
00065 
00066 // Utility functions:
00067 void Ros_MotionServer_ConvertToJointMotionData(SmBodyJointTrajPtFull* jointTrajData, JointMotionData* jointMotionData);
00068 STATUS Ros_MotionServer_DisableEcoMode(Controller* controller);
00069 void Ros_MotionServer_PrintError(USHORT err_no, char* msgPrefix);
00070 
00071 // IO functions:
00072 int Ros_MotionServer_ReadIOBit(SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00073 int Ros_MotionServer_WriteIOBit(SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00074 int Ros_MotionServer_ReadIOGroup(SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00075 int Ros_MotionServer_WriteIOGroup(SimpleMsg* receiveMsg, SimpleMsg* replyMsg);
00076 
00077 
00078 //-----------------------
00079 // Function implementation
00080 //-----------------------
00081 
00082 //-----------------------------------------------------------------------
00083 // Start the tasks for a new motion server connection:
00084 // - WaitForSimpleMsg: Task that waits to receive new SimpleMessage
00085 // - AddToIncQueueProcess: Task that take data from a message and generate Incmove  
00086 //-----------------------------------------------------------------------
00087 void Ros_MotionServer_StartNewConnection(Controller* controller, int sd)
00088 {
00089         int groupNo;
00090         int connectionIndex;
00091         
00092         printf("Starting new connection to the Motion Server\r\n");
00093 
00094         //look for next available connection slot
00095         for (connectionIndex = 0; connectionIndex < MAX_MOTION_CONNECTIONS; connectionIndex++)
00096         {
00097                 if (controller->sdMotionConnections[connectionIndex] == INVALID_SOCKET)
00098                 {
00099                         controller->sdMotionConnections[connectionIndex] = sd;
00100                         break;
00101                 }
00102         }
00103         
00104         if (connectionIndex == MAX_MOTION_CONNECTIONS)
00105         {
00106                 puts("Motion server already connected... not accepting last attempt.");
00107                 mpClose(sd);
00108                 return;
00109         }
00110         
00111         // If not started, start the IncMoveTask (there should be only one instance of this thread)
00112         if(controller->tidIncMoveThread == INVALID_TASK)
00113         {
00114                 puts("Creating new task: IncMoveTask");
00115                 
00116                 controller->tidIncMoveThread = mpCreateTask(MP_PRI_IP_CLK_TAKE, MP_STACK_SIZE, 
00117                                                                                                         (FUNCPTR)Ros_MotionServer_IncMoveLoopStart,
00118                                                                                                         (int)controller, 0, 0, 0, 0, 0, 0, 0, 0, 0);
00119                 if (controller->tidIncMoveThread == ERROR)
00120                 {
00121                         puts("Failed to create task for incremental-motion.  Check robot parameters.");
00122                         mpClose(sd);
00123                         controller->tidIncMoveThread = INVALID_TASK;
00124                         Ros_Controller_SetIOState(IO_FEEDBACK_FAILURE, TRUE);
00125                         return;
00126                 }
00127         }
00128         
00129         // If not started, start the AddToIncQueueProcess for each control group
00130         for(groupNo = 0; groupNo < controller->numGroup; groupNo++)
00131         {
00132                 if (controller->ctrlGroups[groupNo]->tidAddToIncQueue == INVALID_TASK)
00133                 {
00134                         printf("Creating new task: tidAddToIncQueue (groupNo = %d)\n", groupNo);
00135                         
00136                         controller->ctrlGroups[groupNo]->tidAddToIncQueue = mpCreateTask(MP_PRI_TIME_NORMAL, MP_STACK_SIZE, 
00137                                                                                                                                                         (FUNCPTR)Ros_MotionServer_AddToIncQueueProcess,
00138                                                                                                                                                         (int)controller, groupNo, 0, 0, 0, 0, 0, 0, 0, 0); 
00139                         if (controller->ctrlGroups[groupNo]->tidAddToIncQueue == ERROR)
00140                         {
00141                                 puts("Failed to create task for parsing motion increments.  Check robot parameters.");
00142                                 mpClose(sd);
00143                                 controller->ctrlGroups[groupNo]->tidAddToIncQueue = INVALID_TASK;
00144                                 Ros_Controller_SetIOState(IO_FEEDBACK_FAILURE, TRUE);
00145                                 return;
00146                         }
00147                 }
00148         }
00149         
00150 
00151         if (controller->tidMotionConnections[connectionIndex] == INVALID_TASK)
00152         {
00153                 printf("Creating new task: tidMotionConnections (connectionIndex = %d)\n", connectionIndex);
00154                 
00155                         
00156                 //start new task for this specific connection
00157                 controller->tidMotionConnections[connectionIndex] = mpCreateTask(MP_PRI_TIME_NORMAL, MP_STACK_SIZE, 
00158                                                                                                                                                 (FUNCPTR)Ros_MotionServer_WaitForSimpleMsg,
00159                                                                                                                                                 (int)controller, connectionIndex, 0, 0, 0, 0, 0, 0, 0, 0);
00160         
00161                 if (controller->tidMotionConnections[connectionIndex] != ERROR)
00162                 {
00163                         Ros_Controller_SetIOState(IO_FEEDBACK_MOTIONSERVERCONNECTED, TRUE); //set feedback signal indicating success
00164                 }
00165                 else
00166                 {
00167                         puts("Could not create new task in the motion server.  Check robot parameters.");
00168                         mpClose(sd);
00169                         controller->sdMotionConnections[connectionIndex] = INVALID_SOCKET;
00170                         controller->tidMotionConnections[connectionIndex] = INVALID_TASK;
00171                         Ros_Controller_SetIOState(IO_FEEDBACK_FAILURE, TRUE);
00172                         return;
00173                 }
00174         }
00175 }
00176 
00177 
00178 //-----------------------------------------------------------------------
00179 // Close a connection along with all its associated task
00180 //-----------------------------------------------------------------------
00181 void Ros_MotionServer_StopConnection(Controller* controller, int connectionIndex)
00182 {   
00183         int i;
00184         int tid;
00185         BOOL bDeleteIncMovTask;
00186         
00187         printf("Closing Motion Server Connection\r\n");
00188         
00189         //close this connection
00190         mpClose(controller->sdMotionConnections[connectionIndex]);
00191         //mark connection as invalid
00192         controller->sdMotionConnections[connectionIndex] = INVALID_SOCKET;
00193 
00194         // Check if there are still some valid connection
00195         bDeleteIncMovTask = TRUE;
00196         for(i=0; i<MAX_MOTION_CONNECTIONS; i++)
00197         {
00198                 if(controller->sdMotionConnections[connectionIndex] != INVALID_SOCKET)
00199                 {
00200                         bDeleteIncMovTask = FALSE;
00201                         break;
00202                 }
00203         }
00204         
00205         // If there is no more connection, stop the inc_move task
00206         if(bDeleteIncMovTask)
00207         {
00208                 //set feedback signal
00209                 Ros_Controller_SetIOState(IO_FEEDBACK_MOTIONSERVERCONNECTED, FALSE);
00210 
00211                 // Stop adding increment to queue (for each ctrlGroup
00212                 for(i=0; i < controller->numGroup; i++)
00213                 {
00214                         controller->ctrlGroups[i]->hasDataToProcess = FALSE;
00215                         tid = controller->ctrlGroups[i]->tidAddToIncQueue;
00216                         controller->ctrlGroups[i]->tidAddToIncQueue = INVALID_TASK;
00217                         mpDeleteTask(tid);
00218                 }
00219                 
00220                 // terminate the inc_move task
00221                 tid = controller->tidIncMoveThread;
00222                 controller->tidIncMoveThread = INVALID_TASK;
00223                 mpDeleteTask(tid);
00224         }
00225                 
00226         // Stop message receiption task
00227         tid = controller->tidMotionConnections[connectionIndex];
00228         controller->tidMotionConnections[connectionIndex] = INVALID_TASK;
00229         printf("Motion Server Connection Closed\r\n");
00230         
00231         mpDeleteTask(tid);
00232 }
00233 
00234 int Ros_MotionServer_GetExpectedByteSizeForMessageType(SimpleMsg* receiveMsg, int recvByteSize)
00235 {
00236         int minSize = sizeof(SmPrefix) + sizeof(SmHeader);
00237         int expectedSize;
00238 
00239         switch (receiveMsg->header.msgType)
00240         {
00241         case ROS_MSG_ROBOT_STATUS:
00242                 expectedSize = minSize + sizeof(SmBodyRobotStatus);
00243                 break;
00244         case ROS_MSG_JOINT_TRAJ_PT_FULL:
00245                 expectedSize = minSize + sizeof(SmBodyJointTrajPtFull);
00246                 break;
00247         case ROS_MSG_JOINT_FEEDBACK:
00248                 expectedSize = minSize + sizeof(SmBodyJointFeedback);
00249                 break;
00250         case ROS_MSG_MOTO_MOTION_CTRL:
00251                 expectedSize = minSize + sizeof(SmBodyMotoMotionCtrl);
00252                 break;
00253         case ROS_MSG_MOTO_MOTION_REPLY:
00254                 expectedSize = minSize + sizeof(SmBodyMotoMotionReply);
00255                 break;
00256         case ROS_MSG_MOTO_JOINT_TRAJ_PT_FULL_EX:
00257                 //Don't require the user to send data for non-existant control groups
00258                 if (recvByteSize >= (int)(minSize + sizeof(int))) //make sure I can at least get to [numberOfGroups] field
00259                 {
00260                         expectedSize = minSize + (sizeof(int) * 2);
00261                         expectedSize += (sizeof(SmBodyJointTrajPtExData) * receiveMsg->body.jointTrajDataEx.numberOfValidGroups); //check the number of groups to determine size of data
00262                 }
00263                 else
00264                         expectedSize = minSize + sizeof(SmBodyJointTrajPtFullEx);
00265                 break;
00266         case ROS_MSG_MOTO_JOINT_FEEDBACK_EX:
00267                 expectedSize = minSize + sizeof(SmBodyJointFeedbackEx);
00268                 break;
00269         case ROS_MSG_MOTO_READ_IO_BIT:
00270                 expectedSize = minSize + sizeof(SmBodyMotoReadIOBit);
00271                 break;
00272         case ROS_MSG_MOTO_WRITE_IO_BIT:
00273                 expectedSize = minSize + sizeof(SmBodyMotoWriteIOBit);
00274                 break;
00275         case ROS_MSG_MOTO_READ_IO_GROUP:
00276                 expectedSize = minSize + sizeof(SmBodyMotoReadIOGroup);
00277                 break;
00278         case ROS_MSG_MOTO_WRITE_IO_GROUP:
00279                 expectedSize = minSize + sizeof(SmBodyMotoWriteIOGroup);
00280                 break;
00281         default: //invalid message type
00282                 return -1;
00283         }
00284         return expectedSize;
00285 }
00286 
00287 //-----------------------------------------------------------------------
00288 // Task that waits to receive new SimpleMessage and then processes it
00289 //-----------------------------------------------------------------------
00290 void Ros_MotionServer_WaitForSimpleMsg(Controller* controller, int connectionIndex)
00291 {
00292         SimpleMsg receiveMsg;
00293         SimpleMsg replyMsg;
00294         int byteSize = 0, byteSizeResponse = 0;
00295         int minSize = sizeof(SmPrefix) + sizeof(SmHeader);
00296         int expectedSize;
00297         int ret = 0;
00298         BOOL bDisconnect = FALSE;
00299         int partialMsgByteCount = 0;
00300         BOOL bSkipNetworkRecv = FALSE;
00301 
00302         while(!bDisconnect) //keep accepting messages until connection closes
00303         {
00304                 Ros_Sleep(0);   //give it some time to breathe, if needed
00305                 
00306                 if (!bSkipNetworkRecv)
00307                 {
00308                         if (partialMsgByteCount) //partial (incomplete) message already received
00309                         {
00310                                 //Receive message from the PC
00311                                 memset((&receiveMsg) + partialMsgByteCount, 0x00, sizeof(SimpleMsg) - partialMsgByteCount);
00312                                 byteSize = mpRecv(controller->sdMotionConnections[connectionIndex], (char*)((&receiveMsg) + partialMsgByteCount), sizeof(SimpleMsg) - partialMsgByteCount, 0);
00313                                 if (byteSize <= 0)
00314                                         break; //end connection
00315 
00316                                 byteSize += partialMsgByteCount;
00317                                 partialMsgByteCount = 0;
00318                         }
00319                         else //get whole message
00320                         {
00321                                 //Receive message from the PC
00322                                 memset(&receiveMsg, 0x00, sizeof(receiveMsg));
00323                                 byteSize = mpRecv(controller->sdMotionConnections[connectionIndex], (char*)(&receiveMsg), sizeof(SimpleMsg), 0);
00324                                 if (byteSize <= 0)
00325                                         break; //end connection
00326                         }
00327                 }
00328                 else
00329                 {
00330                         byteSize = partialMsgByteCount;
00331                         partialMsgByteCount = 0;
00332                         bSkipNetworkRecv = FALSE;
00333                 }
00334 
00335                 // Determine the expected size of the message
00336                 expectedSize = -1;
00337                 if(byteSize >= minSize)
00338                 {
00339                         expectedSize = Ros_MotionServer_GetExpectedByteSizeForMessageType(&receiveMsg, byteSize);
00340 
00341                         if (expectedSize == -1)
00342                         {
00343                                 printf("Unknown Message Received (%d)\r\n", receiveMsg.header.msgType);
00344                                 Ros_SimpleMsg_MotionReply(&receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_MSGTYPE, &replyMsg, 0);
00345                         }                       
00346                         else if (byteSize >= expectedSize) // Check message size
00347                         {
00348                                 // Process the simple message
00349                                 ret = Ros_MotionServer_SimpleMsgProcess(controller, &receiveMsg, &replyMsg);
00350                                 if (ret == 1) //error during processing
00351                                 {
00352                                         bDisconnect = TRUE;
00353                                 }
00354                                 else if (byteSize > expectedSize) // Received extra data in single message
00355                                 {
00356                                         //Special case where ROS_MSG_MOTO_JOINT_TRAJ_PT_FULL_EX message could have different lengths
00357                                         if (receiveMsg.header.msgType == ROS_MSG_MOTO_JOINT_TRAJ_PT_FULL_EX &&
00358                                                 byteSize == (int)(minSize + sizeof(SmBodyJointTrajPtFullEx)))
00359                                         {
00360                                                 // All good
00361                                                 partialMsgByteCount = 0;
00362                                         }
00363                                         else
00364                                         {
00365                                                 // Preserve the remaining bytes and treat them as the start of a new message
00366                                                 Db_Print("MessageReceived(%d bytes): expectedSize=%d, processing rest of bytes (%d, %d, %d)\r\n", byteSize, expectedSize, sizeof(receiveMsg), receiveMsg.body.jointTrajData.sequence, ((int*)((char*)&receiveMsg + expectedSize))[5]);
00367                                                 partialMsgByteCount = byteSize - expectedSize;
00368                                                 memmove(&receiveMsg, (char*)&receiveMsg + expectedSize, partialMsgByteCount);
00369 
00370                                                 //Did I receive multiple full messages at once that all need to be processed before listening for new data?
00371                                                 if (partialMsgByteCount >= minSize)
00372                                                 {
00373                                                         expectedSize = Ros_MotionServer_GetExpectedByteSizeForMessageType(&receiveMsg, partialMsgByteCount);
00374                                                         bSkipNetworkRecv = (partialMsgByteCount >= expectedSize); //does my modified receiveMsg buffer contain a full message to process?
00375                                                 }
00376                                         }
00377                                 }
00378                                 else // All good
00379                                         partialMsgByteCount = 0;
00380                         }
00381                         else // Not enough data to process the command
00382                         {
00383                                 Db_Print("MessageReceived(%d bytes): expectedSize=%d\r\n", byteSize, expectedSize);
00384                                 Ros_SimpleMsg_MotionReply(&receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_MSGSIZE, &replyMsg, 0);
00385                         }
00386                 }
00387                 else // Didn't even receive a command ID
00388                 {
00389                         Db_Print("Unknown Data Received (%d bytes)\r\n", byteSize);
00390                         Ros_SimpleMsg_MotionReply(&receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_MSGSIZE, &replyMsg, 0);
00391                 }
00392 
00393                 //Send reply message
00394                 byteSizeResponse = mpSend(controller->sdMotionConnections[connectionIndex], (char*)(&replyMsg), replyMsg.prefix.length + sizeof(SmPrefix), 0);
00395                 if (byteSizeResponse <= 0)
00396                         break;  // Close the connection
00397         }
00398         
00399         Ros_Sleep(50);  // Just in case other associated task need time to clean-up.
00400         
00401         //close this connection
00402         Ros_MotionServer_StopConnection(controller, connectionIndex);
00403 }
00404 
00405 
00406 //-----------------------------------------------------------------------
00407 // Checks the type of message and processes it accordingly
00408 // Return -1=Failure; 0=Success; 1=CloseConnection; 
00409 //-----------------------------------------------------------------------
00410 int Ros_MotionServer_SimpleMsgProcess(Controller* controller, SimpleMsg* receiveMsg, SimpleMsg* replyMsg)
00411 {
00412         int ret = 0;
00413         int invalidSubcode = 0;
00414         
00415         switch(receiveMsg->header.msgType)
00416         {
00417         case ROS_MSG_JOINT_TRAJ_PT_FULL:
00418                 ret = Ros_MotionServer_JointTrajDataProcess(controller, receiveMsg, replyMsg);
00419                 break;
00420 
00421         //-----------------------
00422         case ROS_MSG_MOTO_MOTION_CTRL:
00423                 ret = Ros_MotionServer_MotionCtrlProcess(controller, receiveMsg, replyMsg);
00424                 break;
00425 
00426         //-----------------------
00427         case ROS_MSG_MOTO_JOINT_TRAJ_PT_FULL_EX:
00428                 ret = Ros_MotionServer_JointTrajPtFullExProcess(controller, receiveMsg, replyMsg);
00429                 break;
00430 
00431 
00432 //Maintain backward compatibility for users who are sending I/O over motion-server
00433         //-----------------------
00434         case ROS_MSG_MOTO_READ_IO_BIT:
00435                 ret = Ros_IoServer_ReadIOBit(receiveMsg, replyMsg);
00436                 break;
00437 
00438         //-----------------------
00439         case ROS_MSG_MOTO_WRITE_IO_BIT:
00440                 ret = Ros_IoServer_WriteIOBit(receiveMsg, replyMsg);
00441                 break;
00442 
00443         //-----------------------
00444         case ROS_MSG_MOTO_READ_IO_GROUP:
00445                 ret = Ros_IoServer_ReadIOGroup(receiveMsg, replyMsg);
00446                 break;
00447 
00448         //-----------------------
00449         case ROS_MSG_MOTO_WRITE_IO_GROUP:
00450                 ret = Ros_IoServer_WriteIOGroup(receiveMsg, replyMsg);
00451                 break;
00452 
00453         //-----------------------
00454         default:
00455                 printf("Invalid message type: %d\n", receiveMsg->header.msgType);
00456                 invalidSubcode = ROS_RESULT_INVALID_MSGTYPE;
00457                 break;
00458         }
00459         
00460         // Check Invalid Case
00461         if(invalidSubcode != 0)
00462         {
00463                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, invalidSubcode, replyMsg, 0);
00464                 ret = -1;
00465         }
00466                 
00467         return ret;
00468 }
00469 
00470 
00471 //-----------------------------------------------------------------------
00472 // Processes message of type: ROS_MSG_MOTO_JOINT_TRAJ_PT_FULL_EX
00473 // Return -1=Failure; 0=Success; 1=CloseConnection; 
00474 //-----------------------------------------------------------------------
00475 int Ros_MotionServer_JointTrajPtFullExProcess(Controller* controller, SimpleMsg* receiveMsg, 
00476                                                                                           SimpleMsg* replyMsg)
00477 {
00478         SmBodyJointTrajPtFullEx* msgBody;       
00479         CtrlGroup* ctrlGroup;
00480         int ret, i;
00481         FlagsValidFields validationFlags;
00482 
00483         msgBody = &receiveMsg->body.jointTrajDataEx;
00484 
00485         // Check if controller is able to receive incremental move and if the incremental move thread is running
00486         if(!Ros_Controller_IsMotionReady(controller))
00487         {
00488                 int subcode = Ros_Controller_GetNotReadySubcode(controller);
00489                 printf("ERROR: Controller is not ready (code: %d).  Can't process ROS_MSG_MOTO_JOINT_TRAJ_PT_FULL_EX.\r\n", subcode);
00490                 for (i = 0; i < msgBody->numberOfValidGroups; i += 1)
00491                 {
00492                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_NOT_READY, subcode, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00493                 }
00494                 return 0;
00495         }
00496 
00497         // Pre-check to ensure no groups are busy
00498         for (i = 0; i < msgBody->numberOfValidGroups; i += 1)
00499         {
00500                 if (Ros_Controller_IsValidGroupNo(controller, msgBody->jointTrajPtData[i].groupNo))
00501                 {
00502                         ctrlGroup = controller->ctrlGroups[msgBody->jointTrajPtData[i].groupNo];
00503                         if (ctrlGroup->hasDataToProcess)
00504                         {
00505                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_BUSY, 0, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00506                                 return 0;
00507                         }
00508                 }
00509                 else
00510                 {
00511                         printf("ERROR: GroupNo %d is not valid\n", msgBody->jointTrajPtData[i].groupNo);
00512                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_GROUPNO, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00513                         return 0;
00514                 }
00515                         
00516                 // Check that minimum information (time, position, velocity) is valid
00517                 validationFlags = Valid_Time | Valid_Position | Valid_Velocity;
00518                 if( (msgBody->jointTrajPtData[i].validFields & validationFlags) != validationFlags)
00519                 {
00520                         printf("ERROR: Validfields = %d\r\n", msgBody->jointTrajPtData[i].validFields);
00521                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_DATA_INSUFFICIENT, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00522                         return 0;
00523                 }
00524         }
00525 
00526         for (i = 0; i < msgBody->numberOfValidGroups; i += 1)
00527         {
00528                 ctrlGroup = controller->ctrlGroups[msgBody->jointTrajPtData[i].groupNo];
00529                 
00530                 // Check the trajectory sequence code
00531                 if(msgBody->sequence == 0) // First trajectory point
00532                 {
00533                         // Initialize first point variables
00534                         ret = Ros_MotionServer_InitTrajPointFullEx(ctrlGroup, &msgBody->jointTrajPtData[i], msgBody->sequence);
00535                 
00536                         // set reply
00537                         if(ret == 0)
00538                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00539                         else
00540                         {
00541                                 printf("ERROR: Ros_MotionServer_InitTrajPointFullEx returned %d\n", ret);
00542                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ret, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00543                                 return 0; //stop processing other groups in this loop
00544                         }
00545                 }
00546                 else if(msgBody->sequence > 0)// Subsequent trajectory points
00547                 {
00548                         // Add the point to the trajectory
00549                         ret = Ros_MotionServer_AddTrajPointFullEx(ctrlGroup, &msgBody->jointTrajPtData[i], msgBody->sequence);
00550                 
00551                         // ser reply
00552                         if(ret == 0)
00553                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00554                         else if(ret == 1)
00555                         {
00556                                 printf("ERROR: Ros_MotionServer_AddTrajPointFullEx returned %d\n", ret);
00557                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_BUSY, 0, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00558                                 return 0; //stop processing other groups in this loop
00559                         }
00560                         else
00561                         {
00562                                 printf("ERROR: Ros_MotionServer_AddTrajPointFullEx returned %d\n", ret);
00563                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ret, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00564                                 return 0; //stop processing other groups in this loop
00565                         }
00566                 }
00567                 else
00568                 {
00569                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_SEQUENCE, replyMsg, msgBody->jointTrajPtData[i].groupNo);
00570                         return 0; //stop processing other groups in this loop
00571                 }
00572         }
00573 
00574         return 0;
00575 }
00576 
00577 
00578 //-----------------------------------------------------------------------
00579 // Processes message of type: ROS_MSG_MOTO_MOTION_CTRL
00580 // Return -1=Failure; 0=Success; 1=CloseConnection; 
00581 //-----------------------------------------------------------------------
00582 int Ros_MotionServer_MotionCtrlProcess(Controller* controller, SimpleMsg* receiveMsg, 
00583                                                                                 SimpleMsg* replyMsg)
00584 {
00585         SmBodyMotoMotionCtrl* motionCtrl;
00586 
00587         //printf("In MotionCtrlProcess\r\n");
00588 
00589         // Check the command code
00590         motionCtrl = &receiveMsg->body.motionCtrl;
00591         switch(motionCtrl->command)
00592         {
00593                 case ROS_CMD_CHECK_MOTION_READY: 
00594                 {
00595                         if(Ros_Controller_IsMotionReady(controller))
00596                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_TRUE, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00597                         else
00598                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FALSE, Ros_Controller_GetNotReadySubcode(controller), replyMsg, receiveMsg->body.motionCtrl.groupNo);
00599                         break;
00600                 }
00601                 case ROS_CMD_CHECK_QUEUE_CNT:
00602                 {
00603                         int count = Ros_MotionServer_GetQueueCnt(controller, motionCtrl->groupNo);
00604                         if(count >= 0)
00605                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_TRUE, count, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00606                         else
00607                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FAILURE, count, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00608                         break;
00609                 }
00610                 case ROS_CMD_STOP_MOTION:
00611                 {
00612                         // Stop Motion
00613                         BOOL bRet = Ros_MotionServer_StopMotion(controller);
00614                         
00615                         // Reply msg
00616                         if(bRet)
00617                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00618                         else 
00619                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FAILURE, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00620                         break;
00621                 }
00622                 case ROS_CMD_START_SERVOS:
00623                 {
00624                         // Stop Motion
00625                         BOOL bRet = Ros_MotionServer_ServoPower(controller, ON);
00626                         
00627                         // Reply msg
00628                         if(bRet)
00629                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00630                         else 
00631                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FAILURE, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00632                         break;
00633                 }
00634                 case ROS_CMD_STOP_SERVOS:
00635                 {
00636                         // Stop Motion
00637                         BOOL bRet = Ros_MotionServer_ServoPower(controller, OFF);
00638                         
00639                         // Reply msg
00640                         if(bRet)
00641                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00642                         else 
00643                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FAILURE, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00644                         break;
00645                 }
00646                 case ROS_CMD_RESET_ALARM:
00647                 {
00648                         // Stop Motion
00649                         BOOL bRet = Ros_MotionServer_ResetAlarm(controller);
00650                         
00651                         // Reply msg
00652                         if(bRet)
00653                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00654                         else 
00655                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FAILURE, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00656                         break;
00657                 }
00658                 case ROS_CMD_START_TRAJ_MODE:
00659                 {
00660                         // Start Trajectory mode by starting the INIT_ROS job on the controller
00661                         BOOL bRet = Ros_MotionServer_StartTrajMode(controller);
00662                         if(bRet)
00663                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00664                         else
00665                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_NOT_READY, 
00666                                                 Ros_Controller_GetNotReadySubcode(controller), replyMsg, receiveMsg->body.motionCtrl.groupNo);
00667                         break;
00668                 }
00669                 case ROS_CMD_STOP_TRAJ_MODE:
00670                 case ROS_CMD_DISCONNECT:
00671                 {
00672                         BOOL bRet = Ros_MotionServer_StopTrajMode(controller);
00673                         if(bRet)
00674                         {
00675                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00676                                 if(motionCtrl->command == ROS_CMD_DISCONNECT)
00677                                         return 1;
00678                         }
00679                         else
00680                                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_FAILURE, 0, replyMsg, receiveMsg->body.motionCtrl.groupNo);
00681                         break;
00682                 }
00683         }
00684 
00685         return 0;
00686 }
00687 
00688 
00689 //-----------------------------------------------------------------------
00690 // Stop motion by stopping message processing and clearing the queue
00691 //-----------------------------------------------------------------------
00692 BOOL Ros_MotionServer_StopMotion(Controller* controller)
00693 {
00694         // NOTE: for the time being, stop motion will stop all motion for all control group 
00695         BOOL bRet;
00696         BOOL bStopped;
00697         int checkCnt;
00698         int groupNo;
00699                 
00700         // Stop any motion from being processed further
00701         controller->bStopMotion = TRUE;
00702         
00703         // Check that background processing of message has been stopped
00704         for(checkCnt=0; checkCnt<MOTION_STOP_TIMEOUT; checkCnt++) 
00705         {
00706                 bStopped = TRUE;
00707                 for(groupNo=0; groupNo<controller->numGroup; groupNo++)
00708                         bStopped &= !controller->ctrlGroups[groupNo]->hasDataToProcess;
00709                 if(bStopped)
00710                         break;
00711                 else
00712                         Ros_Sleep(1);
00713         }
00714         
00715         // Clear queues
00716         bRet = Ros_MotionServer_ClearQ_All(controller);
00717         
00718         // All motion should be stopped at this point, so turn of the flag
00719         controller->bStopMotion = FALSE;
00720         
00721         return(bStopped && bRet);
00722 }
00723 
00724 
00725 //-----------------------------------------------------------------------
00726 // Sets servo power to ON or OFF
00727 //-----------------------------------------------------------------------
00728 BOOL Ros_MotionServer_ServoPower(Controller* controller, int servoOnOff)
00729 {
00730         MP_SERVO_POWER_SEND_DATA sServoData;
00731         MP_STD_RSP_DATA stdRespData;
00732         int ret;
00733         STATUS status;
00734         
00735 #ifdef DUMMY_SERVO_MODE
00736         return TRUE;
00737 #endif
00738         
00739         if (servoOnOff == OFF)
00740                 Ros_MotionServer_StopMotion(controller);
00741 
00742         if (servoOnOff == ON)
00743         {
00744                 status = Ros_MotionServer_DisableEcoMode(controller);
00745                 if (status == NG)
00746                 {
00747                         Ros_Controller_StatusUpdate(controller);
00748                         return Ros_Controller_IsServoOn(controller) == servoOnOff;
00749                 }
00750         }
00751 
00752         printf("Setting servo power: %d\n", servoOnOff);
00753         memset(&sServoData, 0x00, sizeof(sServoData));
00754         memset(&stdRespData, 0x00, sizeof(stdRespData));
00755         sServoData.sServoPower = servoOnOff;
00756 
00757         ret = mpSetServoPower(&sServoData, &stdRespData);
00758         if( (ret == 0) && (stdRespData.err_no == 0) )
00759         {
00760                 // wait for confirmation
00761                 int checkCount;
00762                 for(checkCount=0; checkCount<MOTION_START_TIMEOUT; checkCount+=MOTION_START_CHECK_PERIOD)
00763                 {
00764                         // Update status
00765                         Ros_Controller_StatusUpdate(controller);
00766                 
00767                         if(Ros_Controller_IsServoOn(controller) == servoOnOff)
00768                                 break;
00769                         
00770                         Ros_Sleep(MOTION_START_CHECK_PERIOD);
00771                 }               
00772         }
00773         else
00774         {
00775                 Ros_MotionServer_PrintError(stdRespData.err_no, "Can't turn off servo because:");
00776         }
00777         
00778         // Update status
00779         Ros_Controller_StatusUpdate(controller);
00780         return Ros_Controller_IsServoOn(controller) == servoOnOff;
00781 }
00782 
00783 BOOL Ros_MotionServer_ResetAlarm(Controller* controller)
00784 {
00785         int ret, i;
00786         BOOL returnBoolean;
00787         MP_ALARM_STATUS_RSP_DATA alarmstatus;
00788         MP_STD_RSP_DATA responseData;
00789         
00790         returnBoolean = TRUE;
00791 
00792         ret = mpGetAlarmStatus(&alarmstatus);
00793         if( ret != 0 ) 
00794         {
00795                 printf("Could not get alarm status\n");
00796                 //Ignore this error.  Continue to try and clear the alarm.
00797         }
00798     
00799         if (alarmstatus.sIsAlarm & MASK_ISALARM_ACTIVEALARM) //alarm is active
00800         {
00801                 MP_ALARM_CODE_RSP_DATA alarmcode;
00802                 ret = mpGetAlarmCode(&alarmcode);
00803                 if( ret != 0 ) 
00804                 {
00805                         printf("Could not get alarm code\n");
00806                         //Ignore this error.  Continue to try and clear the alarm.
00807                 }
00808                 else
00809                 {
00810                         for (i = 0; i < alarmcode.usAlarmNum; i += 1)
00811                                 printf("Has alarm: %d[%d], resetting...\n", alarmcode.AlarmData.usAlarmNo[i], alarmcode.AlarmData.usAlarmData[i]);
00812                 }
00813 
00814                 ret = mpResetAlarm(&responseData);
00815                 if( ret != 0 ) 
00816                 {
00817                         printf("Could not reset the alarm, failure code: %d\n", responseData.err_no);
00818                         returnBoolean = FALSE;
00819                 }
00820         }
00821 
00822         if (alarmstatus.sIsAlarm & MASK_ISALARM_ACTIVEERROR) //error is active
00823         {
00824                 MP_ALARM_CODE_RSP_DATA alarmcode;
00825                 ret = mpGetAlarmCode(&alarmcode);
00826                 if (ret != 0)
00827                 {
00828                         printf("Could not get error code\n");
00829                         //Ignore this problem.  Continue to try and clear the error.
00830                 }
00831                 else
00832                 {
00833                         printf("Has error: %d[%d], resetting...\n", alarmcode.usErrorNo, alarmcode.usErrorData);
00834                 }
00835 
00836                 ret = mpCancelError(&responseData);
00837                 if (ret != 0)
00838                 {
00839                         printf("Could not cancel the error, failure code: %d\n", responseData.err_no);
00840                         returnBoolean = FALSE;
00841                 }
00842         }
00843 
00844         Ros_Controller_StatusUpdate(controller);
00845         return returnBoolean;
00846 }
00847 
00848 //-----------------------------------------------------------------------
00849 // Attempts to start playback of a job to put the controller in RosMotion mode
00850 //-----------------------------------------------------------------------
00851 BOOL Ros_MotionServer_StartTrajMode(Controller* controller)
00852 {
00853         int ret;
00854         MP_STD_RSP_DATA rData;
00855         MP_START_JOB_SEND_DATA sStartData;
00856         int checkCount;
00857         int grpNo;
00858         STATUS status;
00859 
00860         printf("In StartTrajMode\r\n");
00861 
00862         // Update status
00863         Ros_Controller_StatusUpdate(controller);
00864 
00865         // Check if already in the proper mode
00866         if(Ros_Controller_IsMotionReady(controller))
00867                 return TRUE;
00868 
00869         // Check if currently in operation, we don't want to interrupt current operation
00870         if(Ros_Controller_IsOperating(controller))
00871                 return FALSE;
00872                 
00873 #ifndef DUMMY_SERVO_MODE
00874         // Check for condition that need operator manual intervention   
00875         if(Ros_Controller_IsEStop(controller)
00876                 || Ros_Controller_IsHold(controller)
00877                 || !Ros_Controller_IsRemote(controller))
00878                 return FALSE;
00879 #endif
00880                 
00881         // Check for condition that can be fixed remotely
00882         if(Ros_Controller_IsError(controller))
00883         {
00884                 // Cancel error
00885                 memset(&rData, 0x00, sizeof(rData));
00886                 ret = mpCancelError(&rData);
00887                 if(ret != 0)
00888                         goto updateStatus;
00889         }
00890 
00891         // Check for condition that can be fixed remotely
00892         if(Ros_Controller_IsAlarm(controller))
00893         {
00894                 // Reset alarm
00895                 memset(&rData, 0x00, sizeof(rData));
00896                 ret = mpResetAlarm(&rData);
00897                 if(ret == 0)
00898                 {
00899                         // wait for the Alarm reset confirmation
00900                         int checkCount;
00901                         for(checkCount=0; checkCount<MOTION_START_TIMEOUT; checkCount+=MOTION_START_CHECK_PERIOD)
00902                         {
00903                                 // Update status
00904                                 Ros_Controller_StatusUpdate(controller);
00905                 
00906                                 if(Ros_Controller_IsAlarm(controller) == FALSE)
00907                                         continue;
00908                         
00909                                 Ros_Sleep(MOTION_START_CHECK_PERIOD);
00910                         }
00911                         if(Ros_Controller_IsAlarm(controller))
00912                                 goto updateStatus;
00913                 }
00914                 else
00915                         goto updateStatus;
00916         }
00917         
00918 
00919 #ifndef DUMMY_SERVO_MODE
00920         // Servo On
00921         if(Ros_Controller_IsServoOn(controller) == FALSE)
00922         {
00923                 MP_SERVO_POWER_SEND_DATA sServoData;
00924                 memset(&sServoData, 0x00, sizeof(sServoData));
00925 
00926                 status = Ros_MotionServer_DisableEcoMode(controller);
00927                 if (status == NG)
00928                 {
00929                         goto updateStatus;
00930                 }
00931 
00932                 sServoData.sServoPower = 1;  // ON
00933                 memset(&rData, 0x00, sizeof(rData));
00934                 ret = mpSetServoPower(&sServoData, &rData);
00935                 if( (ret == 0) && (rData.err_no ==0) )
00936                 {
00937                         // wait for the Servo On confirmation
00938                         int checkCount;
00939                         for(checkCount=0; checkCount<MOTION_START_TIMEOUT; checkCount+=MOTION_START_CHECK_PERIOD)
00940                         {
00941                                 // Update status
00942                                 Ros_Controller_StatusUpdate(controller);
00943                 
00944                                 if (Ros_Controller_IsServoOn(controller) == TRUE)
00945                                         break;
00946                         
00947                                 Ros_Sleep(MOTION_START_CHECK_PERIOD);
00948                         }
00949                         if(Ros_Controller_IsServoOn(controller) == FALSE)
00950                                 goto updateStatus;                      
00951                 }
00952                 else
00953                 {
00954                         Ros_MotionServer_PrintError(rData.err_no, "Can't turn on servo because:");
00955                         goto updateStatus;                      
00956                 }
00957         }
00958 #endif
00959 
00960         // have to initialize the prevPulsePos that will be used when interpolating the traj
00961         for(grpNo = 0; grpNo < MP_GRP_NUM; ++grpNo)
00962         {
00963                 if(controller->ctrlGroups[grpNo] != NULL)
00964                 {
00965                         Ros_CtrlGroup_GetPulsePosCmd(controller->ctrlGroups[grpNo], controller->ctrlGroups[grpNo]->prevPulsePos);
00966                 }
00967         }
00968 
00969         // Start Job
00970         memset(&rData, 0x00, sizeof(rData));
00971         memset(&sStartData, 0x00, sizeof(sStartData));
00972         sStartData.sTaskNo = 0;
00973         memcpy(sStartData.cJobName, MOTION_INIT_ROS_JOB, MAX_JOB_NAME_LEN);
00974         ret = mpStartJob(&sStartData, &rData);
00975         if( (ret != 0) || (rData.err_no !=0) )
00976         {
00977                 Ros_MotionServer_PrintError(rData.err_no, "Can't start job because:");
00978                 goto updateStatus;              
00979         }
00980         
00981         // wait for the Motion Ready
00982         for(checkCount=0; checkCount<MOTION_START_TIMEOUT; checkCount+=MOTION_START_CHECK_PERIOD)
00983         {
00984                 // Update status
00985                 Ros_Controller_StatusUpdate(controller);
00986                 
00987                 if(Ros_Controller_IsMotionReady(controller))
00988                         return(TRUE);
00989                         
00990                 Ros_Sleep(MOTION_START_CHECK_PERIOD);
00991         }
00992         
00993 updateStatus:   
00994         // Update status
00995         Ros_Controller_StatusUpdate(controller);
00996         
00997         return (Ros_Controller_IsMotionReady(controller));
00998 }
00999 
01000 
01001 
01002 //-----------------------------------------------------------------------
01003 // Set I/O signal matching the WAIT instruction to allow the controller 
01004 // to resume job execution
01005 //-----------------------------------------------------------------------
01006 BOOL Ros_MotionServer_StopTrajMode(Controller* controller)
01007 {
01008         // Don't change mode if queue is not empty
01009         if(Ros_MotionServer_HasDataInQueue(controller))
01010         {
01011                 //printf("Failed: Ros_MotionServer_HasDataInQueue is true\r\n");
01012                 return FALSE;
01013         }
01014                 
01015         // Stop motion
01016         if(!Ros_MotionServer_StopMotion(controller))
01017         {
01018                 //printf("Failed: Ros_MotionServer_StopMotion is false\r\n");
01019                 return FALSE;
01020         }
01021         
01022         // Set I/O signal
01023         Ros_Controller_SetIOState(IO_FEEDBACK_MP_INCMOVE_DONE, TRUE);
01024         
01025         return TRUE;
01026 }
01027 
01028 
01029 //-----------------------------------------------------------------------
01030 // Processes message of type: ROS_MSG_JOINT_TRAJ_PT_FULL
01031 // Return: 0=Success; -1=Failure
01032 //-----------------------------------------------------------------------
01033 int Ros_MotionServer_JointTrajDataProcess(Controller* controller, SimpleMsg* receiveMsg, 
01034                                                                                         SimpleMsg* replyMsg)
01035 {
01036         SmBodyJointTrajPtFull* trajData;
01037         CtrlGroup* ctrlGroup;
01038         int ret;
01039         FlagsValidFields validationFlags;
01040 
01041         // Check if controller is able to receive incremental move and if the incremental move thread is running
01042         if(!Ros_Controller_IsMotionReady(controller))
01043         {
01044                 int subcode = Ros_Controller_GetNotReadySubcode(controller);
01045                 printf("ERROR: Controller is not ready (code: %d).  Can't process ROS_MSG_JOINT_TRAJ_PT_FULL.\r\n", subcode);
01046                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_NOT_READY, subcode, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01047                 return 0;
01048         }
01049 
01050         // Set pointer reference
01051         trajData = &receiveMsg->body.jointTrajData;
01052         
01053         // Check group number valid
01054         if(Ros_Controller_IsValidGroupNo(controller, trajData->groupNo))
01055         {
01056                 ctrlGroup = controller->ctrlGroups[trajData->groupNo];
01057         }
01058         else
01059         {
01060                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_GROUPNO, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01061                 return 0;
01062         }
01063         
01064         // Check that minimum information (time, position, velocity) is valid
01065         validationFlags = Valid_Time | Valid_Position | Valid_Velocity;
01066         if( (trajData->validFields & validationFlags) != validationFlags)
01067         {
01068                 printf("ERROR: Validfields = %d\r\n", trajData->validFields);
01069                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_DATA_INSUFFICIENT, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01070                 return 0;
01071         }
01072 
01073         // Check the trajectory sequence code
01074         if(trajData->sequence == 0) // First trajectory point
01075         {
01076                 // Initialize first point variables
01077                 ret = Ros_MotionServer_InitTrajPointFull(ctrlGroup, trajData);
01078                 
01079                 // set reply
01080                 if(ret == 0)
01081                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01082                 else
01083                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ret, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01084         }
01085         else if(trajData->sequence > 0)// Subsequent trajectory points
01086         {
01087                 // Add the point to the trajectory
01088                 ret = Ros_MotionServer_AddTrajPointFull(ctrlGroup, trajData);
01089                 
01090                 // ser reply
01091                 if(ret == 0)
01092                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_SUCCESS, 0, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01093                 else if(ret == 1)
01094                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_BUSY, 0, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01095                 else
01096                         Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ret, replyMsg, receiveMsg->body.jointTrajData.groupNo);       
01097         }
01098         else
01099         {
01100                 Ros_SimpleMsg_MotionReply(receiveMsg, ROS_RESULT_INVALID, ROS_RESULT_INVALID_SEQUENCE, replyMsg, receiveMsg->body.jointTrajData.groupNo);
01101         }
01102 
01103         return 0;
01104 }
01105 
01106 //-----------------------------------------------------------------------
01107 // Convert SmBodyMotoJointTrajPtExData data to SmBodyJointTrajPtFull
01108 //-----------------------------------------------------------------------
01109 int Ros_MotionServer_InitTrajPointFullEx(CtrlGroup* ctrlGroup, SmBodyJointTrajPtExData* jointTrajDataEx, int sequence)
01110 {
01111         SmBodyJointTrajPtFull jointTrajData;
01112 
01113         //convert SmBodyMotoJointTrajPtExData data to SmBodyJointTrajPtFull
01114         jointTrajData.groupNo = jointTrajDataEx->groupNo;
01115         jointTrajData.sequence = sequence;
01116         jointTrajData.validFields = jointTrajDataEx->validFields;
01117         jointTrajData.time = jointTrajDataEx->time;
01118         memcpy(jointTrajData.pos, jointTrajDataEx->pos, sizeof(float)*ROS_MAX_JOINT);
01119         memcpy(jointTrajData.vel, jointTrajDataEx->vel, sizeof(float)*ROS_MAX_JOINT);
01120         memcpy(jointTrajData.acc, jointTrajDataEx->acc, sizeof(float)*ROS_MAX_JOINT);
01121 
01122         return Ros_MotionServer_InitTrajPointFull(ctrlGroup, &jointTrajData);
01123 }
01124 
01125 //-----------------------------------------------------------------------
01126 // Setup the first point of a trajectory
01127 //-----------------------------------------------------------------------
01128 int Ros_MotionServer_InitTrajPointFull(CtrlGroup* ctrlGroup, SmBodyJointTrajPtFull* jointTrajData)
01129 {
01130         long pulsePos[MAX_PULSE_AXES];
01131         long curPos[MAX_PULSE_AXES];
01132         int i;
01133 
01134         if(ctrlGroup->groupNo == jointTrajData->groupNo)
01135         {
01136                 // Assign start position
01137                 Ros_MotionServer_ConvertToJointMotionData(jointTrajData, &ctrlGroup->jointMotionData);
01138                 ctrlGroup->timeLeftover_ms = 0;
01139                 ctrlGroup->q_time = ctrlGroup->jointMotionData.time;
01140                 
01141                 // For MPL80/100 robot type (SLUBT): Controller automatically moves the B-axis
01142                 // to maintain orientation as other axes are moved.
01143                 if (ctrlGroup->bIsBaxisSlave)
01144                 {
01145                         //ROS joint order
01146                         ctrlGroup->jointMotionData.pos[3] += -ctrlGroup->jointMotionData.pos[1] + ctrlGroup->jointMotionData.pos[2];
01147                         ctrlGroup->jointMotionData.vel[3] += -ctrlGroup->jointMotionData.vel[1] + ctrlGroup->jointMotionData.vel[2];
01148                 }
01149 
01150                 // Convert start position to pulse format
01151                 Ros_CtrlGroup_ConvertToMotoPos(ctrlGroup, ctrlGroup->jointMotionData.pos, pulsePos);
01152                 Ros_CtrlGroup_GetPulsePosCmd(ctrlGroup, curPos);
01153 
01154                 // Initialize prevPulsePos to the current position
01155                 Ros_CtrlGroup_GetPulsePosCmd(ctrlGroup, ctrlGroup->prevPulsePos);
01156                 
01157                 // Check for each axis
01158                 for(i=0; i<MAX_PULSE_AXES; i++)
01159                 {
01160                         // Check if position matches current command position
01161                         if(abs(pulsePos[i] - curPos[i]) > START_MAX_PULSE_DEVIATION)
01162                         {
01163                                 printf("ERROR: Trajectory start position doesn't match current position (MOTO joint order).\r\n");
01164                                 printf(" - Requested start: %ld, %ld, %ld, %ld, %ld, %ld, %ld, %ld\r\n",
01165                                         pulsePos[0], pulsePos[1], pulsePos[2],
01166                                         pulsePos[3], pulsePos[4], pulsePos[5],
01167                                         pulsePos[6], pulsePos[7]);
01168                                 printf(" - Current pos: %ld, %ld, %ld, %ld, %ld, %ld, %ld, %ld\r\n",
01169                                         curPos[0], curPos[1], curPos[2],
01170                                         curPos[3], curPos[4], curPos[5],
01171                                         curPos[6], curPos[7]);
01172                                 printf(" - ctrlGroup->prevPulsePos: %ld, %ld, %ld, %ld, %ld, %ld, %ld, %ld\r\n",
01173                                         ctrlGroup->prevPulsePos[0], ctrlGroup->prevPulsePos[1], ctrlGroup->prevPulsePos[2],
01174                                         ctrlGroup->prevPulsePos[3], ctrlGroup->prevPulsePos[4], ctrlGroup->prevPulsePos[5],
01175                                         ctrlGroup->prevPulsePos[6], ctrlGroup->prevPulsePos[7]);
01176 
01177                                 return ROS_RESULT_INVALID_DATA_START_POS;
01178                         }
01179                         
01180                         // Check maximum velocity limit
01181                         if(abs(ctrlGroup->jointMotionData.vel[i]) > ctrlGroup->maxSpeed[i])
01182                         {
01183                                 // excessive speed
01184                                 return ROS_RESULT_INVALID_DATA_SPEED;
01185                         }
01186                 }               
01187 
01188                 //printf("Trajectory Start Initialized\r\n");
01189                 // Return success
01190                 return 0;
01191         }
01192         
01193         return ROS_RESULT_INVALID_GROUPNO;
01194 }
01195 
01196 //-----------------------------------------------------------------------
01197 // Convert SmBodyMotoJointTrajPtExData data to SmBodyJointTrajPtFull
01198 //-----------------------------------------------------------------------
01199 int Ros_MotionServer_AddTrajPointFullEx(CtrlGroup* ctrlGroup, SmBodyJointTrajPtExData* jointTrajDataEx, int sequence)
01200 {
01201         SmBodyJointTrajPtFull jointTrajData;
01202 
01203         //convert SmBodyMotoJointTrajPtExData data to SmBodyJointTrajPtFull
01204         jointTrajData.groupNo = jointTrajDataEx->groupNo;
01205         jointTrajData.sequence = sequence;
01206         jointTrajData.validFields = jointTrajDataEx->validFields;
01207         jointTrajData.time = jointTrajDataEx->time;
01208         memcpy(jointTrajData.pos, jointTrajDataEx->pos, sizeof(float)*ROS_MAX_JOINT);
01209         memcpy(jointTrajData.vel, jointTrajDataEx->vel, sizeof(float)*ROS_MAX_JOINT);
01210         memcpy(jointTrajData.acc, jointTrajDataEx->acc, sizeof(float)*ROS_MAX_JOINT);
01211 
01212         return Ros_MotionServer_AddTrajPointFull(ctrlGroup, &jointTrajData);
01213 }
01214 
01215 
01216 //-----------------------------------------------------------------------
01217 // Setup the subsequent point of a trajectory
01218 //-----------------------------------------------------------------------
01219 int Ros_MotionServer_AddTrajPointFull(CtrlGroup* ctrlGroup, SmBodyJointTrajPtFull* jointTrajData)
01220 {
01221         int i;
01222         JointMotionData jointData;
01223 
01224         // Check that there isn't data current being processed
01225         if(ctrlGroup->hasDataToProcess)
01226         {
01227                 // Busy
01228                 return ROS_RESULT_BUSY;
01229         }
01230         
01231         // Convert message data to a jointMotionData
01232         Ros_MotionServer_ConvertToJointMotionData(jointTrajData, &jointData);
01233                         
01234         // Check that incoming data is valid
01235         for(i=0; i<ctrlGroup->numAxes; i++)
01236         {
01237                 // Check position softlimit
01238                 // TODO? Note need to add function to Parameter Extraction Library
01239                 
01240                 // Velocity check
01241                 if(abs(jointData.vel[i]) > ctrlGroup->maxSpeed[i])
01242                 {
01243                         // excessive speed
01244                         printf("ERROR: Invalid speed in message TrajPointFull data: \r\n  axis: %d, speed: %f, limit: %f\r\n", 
01245                                 i, jointData.vel[i], ctrlGroup->maxSpeed[i]);
01246                                 
01247                         #ifdef DEBUG
01248                                 Ros_SimpleMsg_DumpTrajPtFull(jointTrajData);
01249                         #endif
01250         
01251                         return ROS_RESULT_INVALID_DATA_SPEED;
01252                 }
01253         }                       
01254 
01255         // Store of the message trajectory data to the control group for processing 
01256         memcpy(&ctrlGroup->jointMotionDataToProcess, &jointData, sizeof(JointMotionData));
01257         ctrlGroup->hasDataToProcess = TRUE;
01258 
01259         return 0;
01260 }
01261 
01262 
01263 //-----------------------------------------------------------------------
01264 // Task that handles in the background messages that may have long processing
01265 // time so that they don't block other message from being processed.
01266 // Checks the type of message and processes it accordingly. 
01267 //-----------------------------------------------------------------------
01268 void Ros_MotionServer_AddToIncQueueProcess(Controller* controller, int groupNo)
01269 {
01270         int interpolPeriod;
01271         CtrlGroup* ctrlGroup = controller->ctrlGroups[groupNo];
01272 
01273         // Initialization of pointers and memory
01274         interpolPeriod = controller->interpolPeriod; 
01275         ctrlGroup->hasDataToProcess = FALSE;
01276 
01277         FOREVER
01278         {
01279                 // if there is no message to process delay and try agsain
01280                 if(ctrlGroup->hasDataToProcess)
01281                 {
01282                         // Interpolate increment move to reach position data
01283                         Ros_MotionServer_JointTrajDataToIncQueue(controller, groupNo);
01284                         
01285                         // Mark message as processed 
01286                         ctrlGroup->hasDataToProcess = FALSE;
01287                 }
01288                 
01289                 Ros_Sleep(interpolPeriod);
01290         }               
01291 }
01292 
01293 
01294 //-----------------------------------------------------------------------
01295 // Decompose the message type: ROS_MSG_JOINT_TRAJ_PT_FULL into incremental
01296 // moves to be added to the inc move queue.
01297 // Interpolation is based on position, velocity and time
01298 // Acceleration is modeled by a linear equation acc = accCoef1 + accCoef2 * time
01299 //-----------------------------------------------------------------------
01300 void Ros_MotionServer_JointTrajDataToIncQueue(Controller* controller, int groupNo)
01301 {
01302         int interpolPeriod = controller->interpolPeriod; 
01303         CtrlGroup* ctrlGroup = controller->ctrlGroups[groupNo];
01304         int i; 
01305         JointMotionData _startTrajData;
01306         JointMotionData* startTrajData;
01307         JointMotionData* endTrajData;
01308         JointMotionData* curTrajData;
01309         float interval;                                         // Time between startTime and the new data time
01310         float accCoef1[MP_GRP_AXES_NUM];    // Acceleration coefficient 1
01311         float accCoef2[MP_GRP_AXES_NUM];    // Acceleration coefficient 2
01312         int timeInc_ms;                                         // time increment in millisecond
01313         int calculationTime_ms;                         // time in ms at which the interpolation takes place
01314         float interpolTime;                             // time increment in second
01315         long newPulsePos[MP_GRP_AXES_NUM];
01316         Incremental_data incData;
01317 
01318         //printf("Starting JointTrajDataProcess\r\n");  
01319 
01320         // Initialization of pointers and memory
01321         curTrajData = &ctrlGroup->jointMotionData;
01322         endTrajData = &ctrlGroup->jointMotionDataToProcess;
01323         startTrajData = &_startTrajData;
01324         // Set the start of the trajectory interpolation as the current position (which should be the end of last interpolation)
01325         memcpy(startTrajData, curTrajData, sizeof(JointMotionData));
01326 
01327         // For MPL80/100 robot type (SLUBT): Controller automatically moves the B-axis
01328         // to maintain orientation as other axes are moved.
01329         if (ctrlGroup->bIsBaxisSlave)
01330         {
01331                 //ROS joint order
01332                 endTrajData->pos[3] += -endTrajData->pos[1] + endTrajData->pos[2];
01333                 endTrajData->vel[3] += -endTrajData->vel[1] + endTrajData->vel[2];
01334         }
01335 
01336         memset(newPulsePos, 0x00, sizeof(newPulsePos));
01337         memset(&incData, 0x00, sizeof(incData));
01338         incData.frame = MP_INC_PULSE_DTYPE;
01339         
01340         // Calculate an acceleration coefficients
01341         memset(&accCoef1, 0x00, sizeof(accCoef1));
01342         memset(&accCoef2, 0x00, sizeof(accCoef2));
01343         interval = (endTrajData->time - startTrajData->time) / 1000.0f;  // time difference in sec
01344         if (interval > 0.0)
01345         {
01346                 for (i = 0; i < ctrlGroup->numAxes; i++)
01347                 {       
01348                         //Calculate acceleration coefficient (convert interval to seconds
01349                         accCoef1[i] = ( 6 * (endTrajData->pos[i] - startTrajData->pos[i]) / (interval * interval) )
01350                                                 - ( 2 * (endTrajData->vel[i] + 2 * startTrajData->vel[i]) / interval);
01351                         accCoef2[i] = ( -12 * (endTrajData->pos[i] - startTrajData->pos[i]) / (interval * interval * interval))
01352                                                 + ( 6 * (endTrajData->vel[i] + startTrajData->vel[i]) / (interval * interval) );
01353                 }
01354         }
01355         else
01356         {
01357                 printf("Warning: Group %d - Time difference between endTrajData (%d) and startTrajData (%d) is 0 or less.\r\n", groupNo, endTrajData->time, startTrajData->time);
01358         }
01359         
01360         // Initialize calculation variable before entering while loop
01361         calculationTime_ms = startTrajData->time;
01362         if(ctrlGroup->timeLeftover_ms == 0)
01363                 timeInc_ms = interpolPeriod;
01364         else
01365                 timeInc_ms = ctrlGroup->timeLeftover_ms;
01366                 
01367         // While interpolation time is smaller than new ROS point time
01368         while( (curTrajData->time < endTrajData->time) && Ros_Controller_IsMotionReady(controller) && !controller->bStopMotion)
01369         {
01370                 // Increment calculation time by next time increment
01371                 calculationTime_ms += timeInc_ms;
01372                 interpolTime = (calculationTime_ms - startTrajData->time) / 1000.0f;
01373                         
01374                 if( calculationTime_ms < endTrajData->time )  // Make calculation for full interpolation clock
01375                 {          
01376                         // Set new interpolation time to calculation time
01377                         curTrajData->time = calculationTime_ms;
01378                                 
01379                         // For each axis calculate the new position at the interpolation time
01380                         for (i = 0; i < ctrlGroup->numAxes; i++)
01381                         {
01382                                 // Add position change for new interpolation time 
01383                                 curTrajData->pos[i] = startTrajData->pos[i]                                             // initial position component
01384                                         + startTrajData->vel[i] * interpolTime                                                  // initial velocity component
01385                                         + accCoef1[i] * interpolTime * interpolTime / 2                                 // accCoef1 component
01386                                         + accCoef2[i] * interpolTime * interpolTime * interpolTime / 6; // accCoef2 component
01387         
01388                                 // Add velocity change for new interpolation time
01389                                 curTrajData->vel[i] = startTrajData->vel[i]                                             // initial velocity component
01390                                         + accCoef1[i] * interpolTime                                                                    // accCoef1 component
01391                                         + accCoef2[i] * interpolTime * interpolTime / 2;                                // accCoef2 component
01392                         }
01393         
01394                         // Reset the timeInc_ms for the next interpolation cycle
01395                         if(timeInc_ms < interpolPeriod)
01396                         {
01397                                 timeInc_ms = interpolPeriod;
01398                                 ctrlGroup->timeLeftover_ms = 0;
01399                         }
01400                 }
01401                 else  // Make calculation for partial interpolation cycle
01402                 {
01403                         // Set the current trajectory data equal to the end trajectory
01404                         memcpy(curTrajData, endTrajData, sizeof(JointMotionData));
01405         
01406                         // Set the next interpolation increment to the the remainder to reach the next interpolation cycle  
01407                         if(calculationTime_ms > endTrajData->time)
01408                         {
01409                                 ctrlGroup->timeLeftover_ms = calculationTime_ms - endTrajData->time;
01410                         } 
01411                 }
01412         
01413                 // Convert position in motoman pulse joint
01414                 Ros_CtrlGroup_ConvertToMotoPos(ctrlGroup, curTrajData->pos, newPulsePos);
01415                 
01416                 // Calculate the increment
01417                 incData.time = curTrajData->time;
01418                 for (i = 0; i < MP_GRP_AXES_NUM; i++)
01419                 {
01420                         if (ctrlGroup->axisType.type[i] != AXIS_INVALID)
01421                                 incData.inc[i] = (newPulsePos[i] - ctrlGroup->prevPulsePos[i]);
01422                         else
01423                                 incData.inc[i] = 0;
01424                 }
01425                 
01426                 // Add the increment to the queue
01427                 if(!Ros_MotionServer_AddPulseIncPointToQ(controller, groupNo, &incData))
01428                         break;
01429                         
01430                 // Copy data to the previous pulse position for next iteration
01431                 memcpy(ctrlGroup->prevPulsePos, newPulsePos, sizeof(ctrlGroup->prevPulsePos));
01432         }
01433 }
01434 
01435 
01436 //-------------------------------------------------------------------
01437 // Adds pulse increments for one interpolation period to the inc move queue
01438 //-------------------------------------------------------------------
01439 BOOL Ros_MotionServer_AddPulseIncPointToQ(Controller* controller, int groupNo, Incremental_data* dataToEnQ)
01440 {       
01441         int index;
01442         
01443         // Set pointer to specified queue
01444         Incremental_q* q = &controller->ctrlGroups[groupNo]->inc_q;
01445 
01446         while( q->cnt >= Q_SIZE ) //queue is full
01447         {
01448                 //wait for items to be removed from the queue
01449                 Ros_Sleep(controller->interpolPeriod);
01450                 
01451                 //make sure we don't get stuck in infinite loop
01452                 if (!Ros_Controller_IsMotionReady(controller)) //<- they probably pressed HOLD or ESTOP
01453                 {
01454                         return FALSE;
01455                 }
01456         }
01457         
01458         // Lock the q before manipulating it
01459         if(mpSemTake(q->q_lock, Q_LOCK_TIMEOUT) == OK)
01460         {
01461                 // Get the index of the end of the queue
01462                 index = Q_OFFSET_IDX( q->idx, q->cnt , Q_SIZE );
01463                 // Copy data at the end of the queue
01464                 q->data[index] = *dataToEnQ;
01465                 // increase the count of elements in the queue
01466                 q->cnt++;
01467                 
01468                 // Unlock the q
01469                 mpSemGive(q->q_lock);
01470         }
01471         else
01472         {
01473                 printf("ERROR: Unable to add point to queue.  Queue is locked up!\r\n");
01474                 return FALSE;
01475         }
01476         
01477         return TRUE;
01478 }
01479 
01480 
01481 //-------------------------------------------------------------------
01482 // Clears the inc move queue
01483 //-------------------------------------------------------------------
01484 BOOL Ros_MotionServer_ClearQ(Controller* controller, int groupNo)
01485 {
01486         Incremental_q* q;
01487 
01488         // Check group number valid
01489         if(!Ros_Controller_IsValidGroupNo(controller, groupNo))
01490                 return FALSE;
01491 
01492         // Set pointer to specified queue
01493         q = &controller->ctrlGroups[groupNo]->inc_q;
01494 
01495         // Lock the q before manipulating it
01496         if(mpSemTake(q->q_lock, Q_LOCK_TIMEOUT) == OK)
01497         {
01498                 // Reset the queue.  No need to modify index or delete data
01499                 q->cnt = 0;
01500                 
01501                 // Unlock the q
01502                 mpSemGive(q->q_lock);
01503                 
01504                 return TRUE;
01505         }
01506 
01507         return FALSE;
01508 }
01509 
01510 
01511 //-------------------------------------------------------------------
01512 // Clears the inc move queue
01513 //-------------------------------------------------------------------
01514 BOOL Ros_MotionServer_ClearQ_All(Controller* controller)
01515 {
01516         int groupNo;
01517         BOOL bRet = TRUE;
01518         
01519         for(groupNo=0; groupNo<controller->numGroup; groupNo++)
01520         {
01521                 bRet &= Ros_MotionServer_ClearQ(controller, groupNo);
01522         }
01523                 
01524         return bRet;
01525 }
01526 
01527 
01528 //-------------------------------------------------------------------
01529 // Check the number of inc_move currently in the specified queue
01530 //-------------------------------------------------------------------
01531 int Ros_MotionServer_GetQueueCnt(Controller* controller, int groupNo)
01532 {
01533         Incremental_q* q;
01534         int count;
01535         
01536         // Check group number valid
01537         if(!Ros_Controller_IsValidGroupNo(controller, groupNo))
01538                 return -1;
01539 
01540         // Set pointer to specified queue
01541         q = &controller->ctrlGroups[groupNo]->inc_q;
01542         
01543         // Lock the q before manipulating it
01544         if(mpSemTake(q->q_lock, Q_LOCK_TIMEOUT) == OK)
01545         {                       
01546                 count = q->cnt;
01547                         
01548                 // Unlock the q
01549                 mpSemGive(q->q_lock);
01550                 
01551                 return count;
01552         }
01553                 
01554         printf("ERROR: Unable to access queue count.  Queue is locked up!\r\n");
01555         return -1;
01556 }
01557 
01558 
01559 
01560 //-------------------------------------------------------------------
01561 // Check that at least one control group of the controller has data in queue
01562 //-------------------------------------------------------------------
01563 BOOL Ros_MotionServer_HasDataInQueue(Controller* controller)
01564 {
01565         int groupNo;
01566         
01567         for(groupNo=0; groupNo<controller->numGroup; groupNo++)
01568         {
01569                 if(Ros_MotionServer_GetQueueCnt(controller, groupNo) > 0)
01570                         return TRUE;
01571         }
01572                 
01573         return FALSE;
01574 }
01575 
01576 
01577 //-------------------------------------------------------------------
01578 // Task to move the robot at each interpolation increment
01579 // 06/05/13: Modified to always send information for all defined groups even if the inc_q is empty
01580 //-------------------------------------------------------------------
01581 void Ros_MotionServer_IncMoveLoopStart(Controller* controller) //<-- IP_CLK priority task
01582 {
01583 #if DX100
01584         MP_POS_DATA moveData;
01585 #else
01586         MP_EXPOS_DATA moveData;
01587 #endif
01588 
01589         Incremental_q* q;
01590         int i;
01591         int ret;
01592         LONG time;
01593         LONG q_time;
01594         int axis;
01595         //BOOL bNoData = TRUE;  // for testing
01596         
01597         printf("IncMoveTask Started\r\n");
01598         
01599         memset(&moveData, 0x00, sizeof(moveData));
01600 
01601         for(i=0; i<controller->numGroup; i++)
01602         {
01603                 moveData.ctrl_grp |= (0x01 << i); 
01604                 moveData.grp_pos_info[i].pos_tag.data[0] = Ros_CtrlGroup_GetAxisConfig(controller->ctrlGroups[i]);
01605         }
01606 
01607         FOREVER
01608         {
01609                 mpClkAnnounce(MP_INTERPOLATION_CLK);
01610                 
01611                 if (Ros_Controller_IsMotionReady(controller) 
01612                         && Ros_MotionServer_HasDataInQueue(controller) 
01613                         && !controller->bStopMotion )
01614                 {
01615                         //bNoData = FALSE;   // for testing
01616                         
01617                         for(i=0; i<controller->numGroup; i++)
01618                         {
01619                                 q = &controller->ctrlGroups[i]->inc_q;
01620 
01621                                 // Lock the q before manipulating it
01622                                 if(mpSemTake(q->q_lock, Q_LOCK_TIMEOUT) == OK)
01623                                 {
01624                                         if(q->cnt > 0)
01625                                         {
01626                                                 time = q->data[q->idx].time;
01627                                                 q_time = controller->ctrlGroups[i]->q_time;
01628                                                 moveData.grp_pos_info[i].pos_tag.data[2] = q->data[q->idx].tool;
01629                                                 moveData.grp_pos_info[i].pos_tag.data[3] = q->data[q->idx].frame;
01630                                                 moveData.grp_pos_info[i].pos_tag.data[4] = q->data[q->idx].user;
01631                                                 
01632                                                 memcpy(&moveData.grp_pos_info[i].pos, &q->data[q->idx].inc, sizeof(LONG) * MP_GRP_AXES_NUM);
01633                                         
01634                                                 // increment index in the queue and decrease the count
01635                                                 q->idx = Q_OFFSET_IDX( q->idx, 1, Q_SIZE );
01636                                                 q->cnt--;
01637                                                 
01638                                                 // Check if complet interpolation period covered
01639                                                 while(q->cnt > 0)
01640                                                 {
01641                                                         if( (q_time <= q->data[q->idx].time) 
01642                                                         &&  (q->data[q->idx].time - q_time <= controller->interpolPeriod) )
01643                                                         { 
01644                                                                 // next incMove is part of same interpolation period
01645                                                                 
01646                                                                 // check that information is in the same format
01647                                                                 if( (moveData.grp_pos_info[i].pos_tag.data[2] != q->data[q->idx].tool)
01648                                                                         || (moveData.grp_pos_info[i].pos_tag.data[3] != q->data[q->idx].frame)
01649                                                                         || (moveData.grp_pos_info[i].pos_tag.data[4] != q->data[q->idx].user) )
01650                                                                 {
01651                                                                         // Different format can't combine information
01652                                                                         break;
01653                                                                 }
01654                                                                 
01655                                                                 // add next incMove to current incMove
01656                                                                 for(axis=0; axis<MP_GRP_AXES_NUM; axis++)
01657                                                                         moveData.grp_pos_info[i].pos[axis] += q->data[q->idx].inc[axis];
01658                                                                 time = q->data[q->idx].time; 
01659 
01660                                                                 // increment index in the queue and decrease the count
01661                                                                 q->idx = Q_OFFSET_IDX( q->idx, 1, Q_SIZE );
01662                                                                 q->cnt--;       
01663                                                         }
01664                                                         else
01665                                                         {
01666                                                                 // interpolation period complet
01667                                                                 break;
01668                                                         }
01669                                                 }
01670                                                 
01671                                                 controller->ctrlGroups[i]->q_time = time;
01672                                         }
01673                                         else
01674                                         {
01675                                                 moveData.grp_pos_info[i].pos_tag.data[2] = 0;
01676                                                 moveData.grp_pos_info[i].pos_tag.data[3] = MP_INC_PULSE_DTYPE;
01677                                                 moveData.grp_pos_info[i].pos_tag.data[4] = 0;
01678                                                 memset(&moveData.grp_pos_info[i].pos, 0x00, sizeof(LONG) * MP_GRP_AXES_NUM);
01679                                         }
01680                                         
01681                                         // Unlock the q                                 
01682                                         mpSemGive(q->q_lock);
01683                                 }
01684                                 else
01685                                 {
01686                                         printf("ERROR: Can't get data from queue. Queue is locked up.\r\n");
01687                                         memset(&moveData.grp_pos_info[i].pos, 0x00, sizeof(LONG) * MP_GRP_AXES_NUM);
01688                                         continue;
01689                                 }
01690                         }       
01691 
01692 #if DX100
01693                         // first robot
01694                         moveData.ctrl_grp = 1;
01695                         ret = mpMeiIncrementMove(MP_SL_ID1, &moveData);
01696                         if(ret != 0)
01697                         {
01698                                 if(ret == -3)
01699                                         printf("mpMeiIncrementMove returned: %d (ctrl_grp = %d)\r\n", ret, moveData.ctrl_grp);
01700                                 else
01701                                         printf("mpMeiIncrementMove returned: %d\r\n", ret);
01702                         }
01703                         // if second robot  // This is not tested but was introduce to help future development
01704                         moveData.ctrl_grp = 2;
01705                         if(controller->numRobot > 1)
01706                         {
01707                                 ret = mpMeiIncrementMove(MP_SL_ID2, &moveData);
01708                                 if(ret != 0)
01709                                 {
01710                                         if(ret == -3)
01711                                                 printf("mpMeiIncrementMove returned: %d (ctrl_grp = %d)\r\n", ret, moveData.ctrl_grp);
01712                                         else
01713                                                 printf("mpMeiIncrementMove returned: %d\r\n", ret);
01714                                 }
01715                         }                       
01716 #else
01717                         ret = mpExRcsIncrementMove(&moveData);
01718                         if(ret != 0)
01719                         {
01720                                 if(ret == -3)
01721                                         printf("mpExRcsIncrementMove returned: %d (ctrl_grp = %d)\r\n", ret, moveData.ctrl_grp);
01722                                 else
01723                                         printf("mpExRcsIncrementMove returned: %d\r\n", ret);
01724                         }
01725 #endif
01726                         
01727                 }
01728                 //else  // for testing
01729                 //{
01730                 //      if(!bNoData)
01731                 //      {
01732                 //              printf("INFO: No data in queue.\r\n");
01733                 //              bNoData = TRUE;
01734                 //      }
01735                 //}
01736         }
01737 }
01738 
01739 
01740 
01741 //-----------------------------------------------------------------------
01742 // Convert a JointTrajData message to a JointMotionData of a control group
01743 //-----------------------------------------------------------------------
01744 void Ros_MotionServer_ConvertToJointMotionData(SmBodyJointTrajPtFull* jointTrajData, JointMotionData* jointMotionData)
01745 {
01746         int i, maxAxes;
01747 
01748         memset(jointMotionData, 0x00, sizeof(JointMotionData));
01749 
01750         maxAxes = min(ROS_MAX_JOINT, MP_GRP_AXES_NUM);
01751         
01752         jointMotionData->flag = jointTrajData->validFields;
01753         jointMotionData->time = (int)(jointTrajData->time * 1000);
01754         
01755         for(i=0; i<maxAxes; i++)
01756         {
01757                 jointMotionData->pos[i] = jointTrajData->pos[i];
01758                 jointMotionData->vel[i] = jointTrajData->vel[i];
01759                 jointMotionData->acc[i] = jointTrajData->acc[i];
01760         }
01761 }
01762 
01763 void Ros_MotionServer_PrintError(USHORT err_no, char* msgPrefix)
01764 {
01765         char errMsg[ERROR_MSG_MAX_SIZE];
01766         memset(errMsg, 0x00, ERROR_MSG_MAX_SIZE);
01767         Ros_Controller_ErrNo_ToString(err_no, errMsg, ERROR_MSG_MAX_SIZE);
01768         printf("%s %s\r\n", msgPrefix, errMsg);
01769 }
01770 
01771 STATUS Ros_MotionServer_DisableEcoMode(Controller* controller)
01772 {
01773         MP_SERVO_POWER_SEND_DATA sServoData;
01774         MP_STD_RSP_DATA rData;
01775         int ret;
01776 
01777 #ifdef DUMMY_SERVO_MODE
01778         return OK;
01779 #endif
01780 
01781         if (Ros_Controller_IsEcoMode(controller) == TRUE)
01782         {
01783                 //toggle servos to disable energy-savings mode
01784                 sServoData.sServoPower = 0;  // OFF
01785                 memset(&sServoData, 0x00, sizeof(sServoData));
01786                 memset(&rData, 0x00, sizeof(rData));
01787                 ret = mpSetServoPower(&sServoData, &rData);
01788                 if ((ret == 0) && (rData.err_no == 0))
01789                 {
01790                         // wait for the Servo/Eco OFF confirmation
01791                         int checkCount;
01792                         for (checkCount = 0; checkCount<MOTION_START_TIMEOUT; checkCount += MOTION_START_CHECK_PERIOD)
01793                         {
01794                                 // Update status
01795                                 Ros_Controller_StatusUpdate(controller);
01796 
01797                                 if (Ros_Controller_IsEcoMode(controller) == FALSE)
01798                                         break;
01799 
01800                                 Ros_Sleep(MOTION_START_CHECK_PERIOD);
01801                         }
01802                 }
01803                 else
01804                 {
01805                         Ros_MotionServer_PrintError(rData.err_no, "Can't disable energy-savings mode because:");
01806                         return NG;
01807                 }
01808         }
01809 
01810         if (Ros_Controller_IsEcoMode(controller) == FALSE)
01811                 return OK;
01812         else
01813                 return NG;
01814 }


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