mpMain.c
Go to the documentation of this file.
00001 /* mp_main.c - MotoPlus Test Application for Real Time Process */
00002 // History:
00003 // 06/12/2013: Fix reply to ROS_MSG_JOINT_TRAJ_PT_FULL message
00004 // 06/12/2013: Release v.1.0.1
00005 // 07/15/2013: Added DX100 compiler option
00006 //                 Change "REMOTE" mode I/O signal to #80011
00007 //                         Listen for skill send
00008 // 08/14/2013: Check initialization success and added extra I/O Feedback 
00009 //             Release v.1.1.1
00010 /*
00011 * Software License Agreement (BSD License) 
00012 *
00013 * Copyright (c) 2013, Yaskawa America, Inc.
00014 * All rights reserved.
00015 *
00016 * Redistribution and use in binary form, with or without modification,
00017 * is permitted provided that the following conditions are met:
00018 *
00019 *       * Redistributions in binary form must reproduce the above copyright
00020 *       notice, this list of conditions and the following disclaimer in the
00021 *       documentation and/or other materials provided with the distribution.
00022 *       * Neither the name of the Yaskawa America, Inc., nor the names 
00023 *       of its contributors may be used to endorse or promote products derived
00024 *       from this software without specific prior written permission.
00025 *
00026 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00027 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00028 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00029 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00030 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00031 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00032 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00033 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00034 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00035 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00036 * POSSIBILITY OF SUCH DAMAGE.
00037 */ 
00038 
00039 #include "motoPlus.h"
00040 #include "ParameterExtraction.h"
00041 #include "CtrlGroup.h"
00042 #include "SimpleMessage.h"
00043 #include "Controller.h"
00044 #include "StateServer.h"
00045 #include "MotionServer.h"
00046 
00047 //GLOBAL DATA DEFINITIONS
00048 
00049 void RosInitTask();
00050 int RosInitTaskID;
00051 
00052 void mpUsrRoot(int arg1, int arg2, int arg3, int arg4, int arg5, int arg6, int arg7, int arg8, int arg9, int arg10)
00053 {
00054 
00055 #ifdef DX100
00056         mpTaskDelay(10000);  // 10 sec. delay to enable DX100 system to complete initialization
00057 #endif
00058         
00059         //Creates and starts a new task in a seperate thread of execution.
00060         //All arguments will be passed to the new task if the function
00061         //prototype will accept them.
00062         RosInitTaskID = mpCreateTask(MP_PRI_TIME_NORMAL, MP_STACK_SIZE, (FUNCPTR)RosInitTask,
00063                                                 arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10);
00064                                                                         
00065         //Ends the initialization task.
00066         mpExitUsrRoot;
00067 }
00068 
00069 void RosInitTask()
00070 {
00071         Controller ros_controller;
00072 
00073         if(!Ros_Controller_Init(&ros_controller))
00074         {
00075                 mpDeleteSelf;
00076                 return;
00077         }
00078 
00079         ros_controller.tidConnectionSrv = mpCreateTask(MP_PRI_TIME_NORMAL, MP_STACK_SIZE, 
00080                                                 (FUNCPTR)Ros_Controller_ConnectionServer_Start,
00081                                                 (int)&ros_controller, 0, 0, 0, 0, 0, 0, 0, 0, 0);
00082                 
00083 #ifdef DX100
00084         // DX100 need to execute a SKILLSEND command prior to the WAIT in order for the 
00085         // incremental motion function to work.  These tasks monitor for those commands
00086         // This supports a maximum of two robots which should be assigned to slave id
00087         // MP_SL_ID1 and MP_SL_ID2 respectively.
00088         
00089         // first robot
00090         ros_controller.RosListenForSkillID[0] = mpCreateTask(MP_PRI_TIME_NORMAL, MP_STACK_SIZE, 
00091                                                 (FUNCPTR)Ros_Controller_ListenForSkill,
00092                                                 (int)&ros_controller, MP_SL_ID1, 0, 0, 0, 0, 0, 0, 0, 0);
00093         // if second robot
00094         if(ros_controller.numRobot > 1)
00095         {
00096                 ros_controller.RosListenForSkillID[1] = mpCreateTask(MP_PRI_TIME_NORMAL, MP_STACK_SIZE, 
00097                                                         (FUNCPTR)Ros_Controller_ListenForSkill,
00098                                                         (int)&ros_controller, MP_SL_ID2, 0, 0, 0, 0, 0, 0, 0, 0);       
00099         }
00100         else
00101         {
00102                 ros_controller.RosListenForSkillID[1] = INVALID_TASK;
00103         }
00104 #endif
00105                 
00106         // start loop to monitor controller state
00107         FOREVER
00108         {
00109                 // Check controller status
00110                 Ros_Controller_StatusUpdate(&ros_controller);
00111         
00112                 mpTaskDelay(CONTROLLER_STATUS_UPDATE_PERIOD);
00113         }
00114 }
00115 
00116 
00117 


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