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 TCP_PORT_MOTION                                         50240
00036 #define TCP_PORT_STATE                                          50241
00037 #define TCP_PORT_IO                                                     50242
00038 
00039 #define IO_FEEDBACK_WAITING_MP_INCMOVE          11120  //output# 889 
00040 #define IO_FEEDBACK_MP_INCMOVE_DONE                     11121  //output# 890 
00041 #define IO_FEEDBACK_INITIALIZATION_DONE         11122  //output# 891 
00042 #define IO_FEEDBACK_CONNECTSERVERRUNNING        11123  //output# 892 
00043 #define IO_FEEDBACK_MOTIONSERVERCONNECTED       11124  //output# 893 
00044 #define IO_FEEDBACK_STATESERVERCONNECTED        11125  //output# 894 
00045 #define IO_FEEDBACK_IOSERVERCONNECTED           11126  //output# 895 
00046 #define IO_FEEDBACK_FAILURE                                     11127  //output# 896
00047 
00048 #define IO_FEEDBACK_RESERVED_1                          11130  //output# 897 
00049 #define IO_FEEDBACK_RESERVED_2                          11131  //output# 898 
00050 #define IO_FEEDBACK_RESERVED_3                          11132  //output# 899 
00051 #define IO_FEEDBACK_RESERVED_4                          11133  //output# 900 
00052 #define IO_FEEDBACK_RESERVED_5                          11134  //output# 901 
00053 #define IO_FEEDBACK_RESERVED_6                          11135  //output# 902 
00054 #define IO_FEEDBACK_RESERVED_7                          11136  //output# 903
00055 #define IO_FEEDBACK_RESERVED_8                          11137  //output# 904 
00056 
00057 #define MAX_IO_CONNECTIONS      1
00058 #define MAX_MOTION_CONNECTIONS  1
00059 #define MAX_STATE_CONNECTIONS   4
00060 
00061 #define INVALID_SOCKET -1
00062 #define INVALID_TASK -1
00063 
00064 #ifndef IPPROTO_TCP
00065 #define IPPROTO_TCP  6
00066 #endif
00067 
00068 #define ERROR_MSG_MAX_SIZE 64
00069 
00070 #define START_MAX_PULSE_DEVIATION 10
00071 
00072 #define CONTROLLER_STATUS_UPDATE_PERIOD 10
00073 
00074 #define MASK_ISALARM_ACTIVEALARM 0x02
00075 #define MASK_ISALARM_ACTIVEERROR 0x01
00076 
00077 typedef enum 
00078 {
00079         IO_ROBOTSTATUS_ALARM_MAJOR = 0,
00080         IO_ROBOTSTATUS_ALARM_MINOR,
00081         IO_ROBOTSTATUS_ALARM_SYSTEM,
00082         IO_ROBOTSTATUS_ALARM_USER,
00083         IO_ROBOTSTATUS_ERROR,
00084         IO_ROBOTSTATUS_PLAY,
00085         IO_ROBOTSTATUS_TEACH,
00086         IO_ROBOTSTATUS_REMOTE,
00087         IO_ROBOTSTATUS_OPERATING,
00088         IO_ROBOTSTATUS_HOLD,
00089         IO_ROBOTSTATUS_SERVO,
00090         IO_ROBOTSTATUS_ESTOP_EX,
00091         IO_ROBOTSTATUS_ESTOP_PP,
00092         IO_ROBOTSTATUS_ESTOP_CTRL,
00093         IO_ROBOTSTATUS_WAITING_ROS,
00094         IO_ROBOTSTATUS_INECOMODE,
00095         IO_ROBOTSTATUS_MAX
00096 } IoStatusIndex;
00097  
00098 typedef struct
00099 {
00100         UINT16 interpolPeriod;                                                                  // Interpolation period of the controller
00101         int numGroup;                                                                                   // Actual number of defined group
00102         int numRobot;                                                                                   // Actual number of defined robot
00103         CtrlGroup* ctrlGroups[MP_GRP_NUM];                                              // Array of the controller control group
00104 
00105         // Controller Status
00106         MP_IO_INFO ioStatusAddr[IO_ROBOTSTATUS_MAX];                    // Array of Specific Input Address representing the I/O status
00107         USHORT ioStatus[IO_ROBOTSTATUS_MAX];                                    // Array storing the current status of the controller
00108         int alarmCode;                                                                                  // Alarm number currently active
00109         BOOL bRobotJobReady;                                                                    // Boolean indicating that the controller is ready for increment move
00110         BOOL bRobotJobReadyRaised;                                                              // Indicates that the signal was raised since operating was resumed
00111         BOOL bStopMotion;                                                                               // Flag to stop motion
00112 
00113         // Connection Server
00114         int tidConnectionSrv;
00115 
00116         // Io Server Connection
00117         int     sdIoConnections[MAX_IO_CONNECTIONS];                            // Socket Descriptor array for Io Server
00118         int     tidIoConnections[MAX_IO_CONNECTIONS];                           // ThreadId array for Io Server
00119 
00120         // State Server Connection
00121         int tidStateSendState;                                                                  // ThreadId of thread sending the controller state
00122         int     sdStateConnections[MAX_STATE_CONNECTIONS];                      // Socket Descriptor array for State Server
00123 
00124         // Motion Server Connection
00125         int     sdMotionConnections[MAX_MOTION_CONNECTIONS];            // Socket Descriptor array for Motion Server
00126         int     tidMotionConnections[MAX_MOTION_CONNECTIONS];           // ThreadId array for Motion Server
00127         int tidIncMoveThread;                                                                   // ThreadId for sending the incremental move to the controller
00128 
00129 #ifdef DX100
00130         BOOL bSkillMotionReady[2];                                                              // Boolean indicating that the SKILL command required for DX100 is active
00131         int RosListenForSkillID[2];                                                             // ThreadId for listening to SkillSend command
00132 #endif
00133 
00134 } Controller;
00135 
00136 extern BOOL Ros_Controller_Init(Controller* controller);
00137 extern BOOL Ros_Controller_IsValidGroupNo(Controller* controller, int groupNo);
00138 extern void Ros_Controller_ConnectionServer_Start(Controller* controller);
00139 
00140 extern void Ros_Controller_StatusInit(Controller* controller);
00141 extern BOOL Ros_Controller_StatusRead(Controller* controller, USHORT ioStatus[IO_ROBOTSTATUS_MAX]);
00142 extern BOOL Ros_Controller_StatusUpdate(Controller* controller);
00143 extern BOOL Ros_Controller_IsAlarm(Controller* controller);
00144 extern BOOL Ros_Controller_IsError(Controller* controller);
00145 extern BOOL Ros_Controller_IsPlay(Controller* controller);
00146 extern BOOL Ros_Controller_IsTeach(Controller* controller);
00147 extern BOOL Ros_Controller_IsRemote(Controller* controller);
00148 extern BOOL Ros_Controller_IsOperating(Controller* controller);
00149 extern BOOL Ros_Controller_IsHold(Controller* controller);
00150 extern BOOL Ros_Controller_IsServoOn(Controller* controller);
00151 extern BOOL Ros_Controller_IsEcoMode(Controller* controller);
00152 extern BOOL Ros_Controller_IsEStop(Controller* controller);
00153 extern BOOL Ros_Controller_IsWaitingRos(Controller* controller);
00154 extern BOOL Ros_Controller_IsMotionReady(Controller* controller);
00155 extern int Ros_Controller_GetNotReadySubcode(Controller* controller);
00156 extern int Ros_Controller_StatusToMsg(Controller* controller, SimpleMsg* sendMsg);
00157 
00158 extern BOOL Ros_Controller_GetIOState(ULONG signal);
00159 extern void Ros_Controller_SetIOState(ULONG signal, BOOL status);
00160 extern void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize);
00161 
00162 #ifdef DX100
00163 extern void Ros_Controller_ListenForSkill(Controller* controller, int sl);
00164 #endif
00165 
00166 typedef enum
00167 {
00168         SUBCODE_INVALID_AXIS_TYPE
00169 } ROS_ASSERTION_CODE;
00170 extern void motoRosAssert(BOOL mustBeTrue, ROS_ASSERTION_CODE subCodeIfFalse, char* msgFmtIfFalse, ...);
00171 
00172 extern void Db_Print(char* msgFormat, ...);
00173 
00174 extern void Ros_Sleep(float milliseconds);
00175 
00176 //#define DUMMY_SERVO_MODE 1    // Dummy servo mode is used for testing with Yaskawa debug controllers
00177 #ifdef DUMMY_SERVO_MODE
00178 #warning Dont forget to disable DUMMY_SERO_MODE when done testing
00179 #endif
00180 
00181 #endif


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