Controller.h
Go to the documentation of this file.
00001 //Controller.h
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 #ifndef CONTROLLER_H
00033 #define CONTROLLER_H
00034 
00035 //#define DX100          // Define to compile for DX100 controller  
00036 
00037 #define TCP_PORT_MOTION 50240
00038 #define TCP_PORT_STATE  50241
00039 
00040 #define IO_FEEDBACK_WAITING_MP_INCMOVE    11120  //output# 889 
00041 #define IO_FEEDBACK_MP_INCMOVE_DONE               11121  //output# 890 
00042 #define IO_FEEDBACK_INITIALIZATION_DONE   11122  //output# 891 
00043 #define IO_FEEDBACK_CONNECTSERVERRUNNING  11123  //output# 892 
00044 #define IO_FEEDBACK_MOTIONSERVERCONNECTED 11124  //output# 893 
00045 #define IO_FEEDBACK_STATESERVERCONNECTED  11125  //output# 894 
00046 #define IO_FEEDBACK_FAILURE                               11127  //output# 896
00047 
00048 #define IO_
00049 
00050 #define MAX_MOTION_CONNECTIONS  1
00051 #define MAX_STATE_CONNECTIONS   4
00052 
00053 #define INVALID_SOCKET -1
00054 #define INVALID_TASK -1
00055 #define IPPROTO_TCP  6
00056 
00057 #define ERROR_MSG_MAX_SIZE 64
00058 
00059 #define START_MAX_PULSE_DEVIATION 10
00060 
00061 #define CONTROLLER_STATUS_UPDATE_PERIOD 10
00062 
00063 typedef enum 
00064 {
00065         IOSTATUS_ALARM_MAJOR = 0,
00066         IOSTATUS_ALARM_MINOR,
00067         IOSTATUS_ALARM_SYSTEM,
00068         IOSTATUS_ALARM_USER,
00069         IOSTATUS_ERROR,
00070         IOSTATUS_PLAY,
00071         IOSTATUS_TEACH,
00072         IOSTATUS_REMOTE,
00073         IOSTATUS_OPERATING,
00074         IOSTATUS_HOLD,
00075         IOSTATUS_SERVO,
00076         IOSTATUS_ESTOP_EX,
00077         IOSTATUS_ESTOP_PP,
00078         IOSTATUS_ESTOP_CTRL,
00079         IOSTATUS_WAITING_ROS,
00080         IOSTATUS_MAX
00081 } IoStatusIndex;
00082  
00083 typedef struct
00084 {
00085         UINT16 interpolPeriod;                                                                  // Interpolation period of the controller
00086         int numGroup;                                                                                   // Actual number of defined group
00087         int numRobot;                                                                                   // Actual number of defined robot
00088         CtrlGroup* ctrlGroups[MP_GRP_NUM];                                              // Array of the controller control group
00089         
00090         // Controller Status
00091         MP_IO_INFO ioStatusAddr[IOSTATUS_MAX];                                  // Array of Specific Input Address representing the I/O status
00092     USHORT ioStatus[IOSTATUS_MAX];                                                      // Array storing the current status of the controller
00093     int alarmCode;                                                                                      // Alarm number currently active
00094         BOOL bRobotJobReady;                                                                    // Boolean indicating that the controller is ready for increment move
00095     BOOL bRobotJobReadyRaised;                                                          // Indicates that the signal was raised since operating was resumed
00096     BOOL bStopMotion;                                                                           // Flag to stop motion
00097 
00098         // Connection Server
00099         int tidConnectionSrv;
00100         
00101         // State Server Connection
00102         int tidStateSendState;                                                                  // ThreadId of thread sending the controller state
00103         int     sdStateConnections[MAX_STATE_CONNECTIONS];                      // Socket Descriptor array for State Server
00104 
00105         // Motion Server Connection
00106         int     sdMotionConnections[MAX_MOTION_CONNECTIONS];            // Socket Descriptor array for Motion Server
00107         int     tidMotionConnections[MAX_MOTION_CONNECTIONS];           // ThreadId array for Motion Server
00108         int tidIncMoveThread;                                                                   // ThreadId for sending the incremental move to the controller
00109 
00110 #ifdef DX100
00111         BOOL bSkillMotionReady[2];                                                              // Boolean indicating that the SKILL command required for DX100 is active
00112         int RosListenForSkillID[2];                                                             // ThreadId for listening to SkillSend command
00113 #endif
00114         
00115 } Controller;
00116 
00117 extern BOOL Ros_Controller_Init(Controller* controller);
00118 extern BOOL Ros_Controller_IsValidGroupNo(Controller* controller, int groupNo);
00119 extern void Ros_Controller_ConnectionServer_Start(Controller* controller);
00120 
00121 extern void Ros_Controller_StatusInit(Controller* controller);
00122 extern BOOL Ros_Controller_StatusRead(Controller* controller, USHORT ioStatus[IOSTATUS_MAX]);
00123 extern BOOL Ros_Controller_StatusUpdate(Controller* controller);
00124 extern BOOL Ros_Controller_IsAlarm(Controller* controller);
00125 extern BOOL Ros_Controller_IsError(Controller* controller);
00126 extern BOOL Ros_Controller_IsPlay(Controller* controller);
00127 extern BOOL Ros_Controller_IsTeach(Controller* controller);
00128 extern BOOL Ros_Controller_IsRemote(Controller* controller);
00129 extern BOOL Ros_Controller_IsOperating(Controller* controller);
00130 extern BOOL Ros_Controller_IsHold(Controller* controller);
00131 extern BOOL Ros_Controller_IsServoOn(Controller* controller);
00132 extern BOOL Ros_Controller_IsEStop(Controller* controller);
00133 extern BOOL Ros_Controller_IsWaitingRos(Controller* controller);
00134 extern BOOL Ros_Controller_IsMotionReady(Controller* controller);
00135 extern int Ros_Controller_GetNotReadySubcode(Controller* controller);
00136 extern int Ros_Controller_StatusToMsg(Controller* controller, SimpleMsg* sendMsg);
00137 
00138 extern BOOL Ros_Controller_GetIOState(ULONG signal);
00139 extern void Ros_Controller_SetIOState(ULONG signal, BOOL status);
00140 extern void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize);
00141 
00142 #ifdef DX100
00143 extern void Ros_Controller_ListenForSkill(Controller* controller, int sl);
00144 #endif
00145 
00146 #endif


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