Controller.h
Go to the documentation of this file.
1 //Controller.h
2 //
3 /*
4 * Software License Agreement (BSD License)
5 *
6 * Copyright (c) 2013, Yaskawa America, Inc.
7 * All rights reserved.
8 *
9 * Redistribution and use in binary form, with or without modification,
10 * is permitted provided that the following conditions are met:
11 *
12 * * Redistributions in binary form must reproduce the above copyright
13 * notice, this list of conditions and the following disclaimer in the
14 * documentation and/or other materials provided with the distribution.
15 * * Neither the name of the Yaskawa America, Inc., nor the names
16 * of its contributors may be used to endorse or promote products derived
17 * from this software without specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
23 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 */
31 
32 #ifndef CONTROLLER_H
33 #define CONTROLLER_H
34 
35 #define TCP_PORT_MOTION 50240
36 #define TCP_PORT_STATE 50241
37 #define TCP_PORT_IO 50242
38 
39 #define IO_FEEDBACK_WAITING_MP_INCMOVE 11120 //output# 889
40 #define IO_FEEDBACK_MP_INCMOVE_DONE 11121 //output# 890
41 #define IO_FEEDBACK_INITIALIZATION_DONE 11122 //output# 891
42 #define IO_FEEDBACK_CONNECTSERVERRUNNING 11123 //output# 892
43 #define IO_FEEDBACK_MOTIONSERVERCONNECTED 11124 //output# 893
44 #define IO_FEEDBACK_STATESERVERCONNECTED 11125 //output# 894
45 #define IO_FEEDBACK_IOSERVERCONNECTED 11126 //output# 895
46 #define IO_FEEDBACK_FAILURE 11127 //output# 896
47 
48 #define IO_FEEDBACK_RESERVED_1 11130 //output# 897
49 #define IO_FEEDBACK_RESERVED_2 11131 //output# 898
50 #define IO_FEEDBACK_RESERVED_3 11132 //output# 899
51 #define IO_FEEDBACK_RESERVED_4 11133 //output# 900
52 #define IO_FEEDBACK_RESERVED_5 11134 //output# 901
53 #define IO_FEEDBACK_RESERVED_6 11135 //output# 902
54 #define IO_FEEDBACK_RESERVED_7 11136 //output# 903
55 #define IO_FEEDBACK_RESERVED_8 11137 //output# 904
56 
57 #define MAX_IO_CONNECTIONS 1
58 #define MAX_MOTION_CONNECTIONS 1
59 #define MAX_STATE_CONNECTIONS 4
60 
61 #if (DX100)
62  #define MAX_CONTROLLABLE_GROUPS 3
63 #else
64  #define MAX_CONTROLLABLE_GROUPS 4
65 #endif
66 
67 #define INVALID_SOCKET -1
68 #define INVALID_TASK -1
69 
70 #ifndef IPPROTO_TCP
71 #define IPPROTO_TCP 6
72 #endif
73 
74 #define ERROR_MSG_MAX_SIZE 64
75 
76 #define START_MAX_PULSE_DEVIATION 30
77 
78 #define CONTROLLER_STATUS_UPDATE_PERIOD 10
79 
80 #define MASK_ISALARM_ACTIVEALARM 0x02
81 #define MASK_ISALARM_ACTIVEERROR 0x01
82 
83 typedef enum
84 {
101 #if (YRC1000||YRC1000u)
102  IO_ROBOTSTATUS_PFL_STOP,
103  IO_ROBOTSTATUS_PFL_ESCAPE,
104  IO_ROBOTSTATUS_PFL_AVOIDING,
105  IO_ROBOTSTATUS_PFL_AVOID_JOINT,
106  IO_ROBOTSTATUS_PFL_AVOID_TRANS,
107 #endif
109 } IoStatusIndex;
110 
111 typedef struct
112 {
113  UINT16 interpolPeriod; // Interpolation period of the controller
114  int numGroup; // Actual number of defined group
115  int numRobot; // Actual number of defined robot
116  CtrlGroup* ctrlGroups[MP_GRP_NUM]; // Array of the controller control group
117 
118  // Controller Status
119  MP_IO_INFO ioStatusAddr[IO_ROBOTSTATUS_MAX]; // Array of Specific Input Address representing the I/O status
120  USHORT ioStatus[IO_ROBOTSTATUS_MAX]; // Array storing the current status of the controller
121  int alarmCode; // Alarm number currently active
122  BOOL bRobotJobReady; // Indicates the robot job is on the WAIT command (ready for motion)
123  BOOL bStopMotion; // Flag to stop motion
124  BOOL bPFLduringRosMove; // Flag to keep track PFL activation during RosMotion
125 
126  // Connection Server
128 
129  // Io Server Connection
130  int sdIoConnections[MAX_IO_CONNECTIONS]; // Socket Descriptor array for Io Server
131  int tidIoConnections[MAX_IO_CONNECTIONS]; // ThreadId array for Io Server
132 
133  // State Server Connection
134  int tidStateSendState[MAX_STATE_CONNECTIONS]; // ThreadId of thread sending the controller state
135  int sdStateConnections[MAX_STATE_CONNECTIONS]; // Socket Descriptor array for State Server
136 
137  // Motion Server Connection
138  int sdMotionConnections[MAX_MOTION_CONNECTIONS]; // Socket Descriptor array for Motion Server
139  int tidMotionConnections[MAX_MOTION_CONNECTIONS]; // ThreadId array for Motion Server
140  int tidIncMoveThread; // ThreadId for sending the incremental move to the controller
141 
142 #ifdef DX100
143  BOOL bSkillMotionReady[2]; // Boolean indicating that the SKILL command required for DX100 is active
144  int RosListenForSkillID[2]; // ThreadId for listening to SkillSend command
145  BOOL bIsDx100Sda; // Special case to control the waist axis (axis 15)
146 #endif
147 
148 } Controller;
149 
150 extern BOOL Ros_Controller_Init(Controller* controller);
151 extern BOOL Ros_Controller_IsValidGroupNo(Controller* controller, int groupNo);
152 extern void Ros_Controller_ConnectionServer_Start(Controller* controller);
153 
154 extern void Ros_Controller_StatusInit(Controller* controller);
155 extern BOOL Ros_Controller_StatusRead(Controller* controller, USHORT ioStatus[IO_ROBOTSTATUS_MAX]);
156 extern BOOL Ros_Controller_StatusUpdate(Controller* controller);
157 extern BOOL Ros_Controller_IsAlarm(Controller* controller);
158 extern BOOL Ros_Controller_IsError(Controller* controller);
159 extern BOOL Ros_Controller_IsPlay(Controller* controller);
160 extern BOOL Ros_Controller_IsTeach(Controller* controller);
161 extern BOOL Ros_Controller_IsRemote(Controller* controller);
162 extern BOOL Ros_Controller_IsOperating(Controller* controller);
163 extern BOOL Ros_Controller_IsHold(Controller* controller);
164 extern BOOL Ros_Controller_IsServoOn(Controller* controller);
165 extern BOOL Ros_Controller_IsEcoMode(Controller* controller);
166 extern BOOL Ros_Controller_IsEStop(Controller* controller);
167 extern BOOL Ros_Controller_IsWaitingRos(Controller* controller);
168 extern BOOL Ros_Controller_IsMotionReady(Controller* controller);
169 extern BOOL Ros_Controller_IsPflActive(Controller* controller);
170 extern int Ros_Controller_GetNotReadySubcode(Controller* controller);
171 extern int Ros_Controller_StatusToMsg(Controller* controller, SimpleMsg* sendMsg);
172 
173 extern BOOL Ros_Controller_GetIOState(ULONG signal);
174 extern void Ros_Controller_SetIOState(ULONG signal, BOOL status);
175 extern void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize);
176 
177 #ifdef DX100
178 extern void Ros_Controller_ListenForSkill(Controller* controller, int sl);
179 #endif
180 
181 typedef enum
182 {
185 extern void motoRosAssert(BOOL mustBeTrue, ROS_ASSERTION_CODE subCodeIfFalse, char* msgFmtIfFalse, ...);
186 
187 extern void Db_Print(char* msgFormat, ...);
188 
189 extern void Ros_Sleep(float milliseconds);
190 
191 //#define DUMMY_SERVO_MODE 1 // Dummy servo mode is used for testing with Yaskawa debug controllers
192 #ifdef DUMMY_SERVO_MODE
193 #warning Dont forget to disable DUMMY_SERO_MODE when done testing
194 #endif
195 
196 #endif
BOOL Ros_Controller_Init(Controller *controller)
Definition: Controller.c:99
BOOL Ros_Controller_StatusRead(Controller *controller, USHORT ioStatus[IO_ROBOTSTATUS_MAX])
Definition: Controller.c:687
BOOL bStopMotion
Definition: Controller.h:123
int Ros_Controller_StatusToMsg(Controller *controller, SimpleMsg *sendMsg)
Definition: Controller.c:656
void Ros_Controller_SetIOState(ULONG signal, BOOL status)
Definition: Controller.c:793
int tidConnectionSrv
Definition: Controller.h:127
void Ros_Sleep(float milliseconds)
Definition: Controller.c:999
void Db_Print(char *msgFormat,...)
Definition: Controller.c:982
int groupNo
BOOL Ros_Controller_IsHold(Controller *controller)
Definition: Controller.c:493
BOOL Ros_Controller_IsEcoMode(Controller *controller)
Definition: Controller.c:503
int numRobot
Definition: Controller.h:115
#define ERROR_MSG_MAX_SIZE
Definition: Controller.h:74
void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize)
Definition: Controller.c:828
BOOL Ros_Controller_IsError(Controller *controller)
Definition: Controller.c:468
#define MAX_STATE_CONNECTIONS
Definition: Controller.h:59
BOOL bPFLduringRosMove
Definition: Controller.h:124
void Ros_Controller_StatusInit(Controller *controller)
Definition: Controller.c:431
BOOL Ros_Controller_IsEStop(Controller *controller)
Definition: Controller.c:508
BOOL Ros_Controller_IsOperating(Controller *controller)
Definition: Controller.c:488
BOOL Ros_Controller_IsPlay(Controller *controller)
Definition: Controller.c:473
ROS_ASSERTION_CODE
Definition: Controller.h:181
BOOL Ros_Controller_IsTeach(Controller *controller)
Definition: Controller.c:478
BOOL Ros_Controller_IsValidGroupNo(Controller *controller, int groupNo)
Definition: Controller.c:255
BOOL Ros_Controller_IsAlarm(Controller *controller)
Definition: Controller.c:460
BOOL bRobotJobReady
Definition: Controller.h:122
BOOL Ros_Controller_IsRemote(Controller *controller)
Definition: Controller.c:483
BOOL Ros_Controller_IsServoOn(Controller *controller)
Definition: Controller.c:498
BOOL Ros_Controller_IsPflActive(Controller *controller)
Definition: Controller.c:543
int numGroup
Definition: Controller.h:114
void Ros_Controller_ConnectionServer_Start(Controller *controller)
Definition: Controller.c:314
UINT16 interpolPeriod
Definition: Controller.h:113
BOOL Ros_Controller_GetIOState(ULONG signal)
Definition: Controller.c:774
#define MAX_MOTION_CONNECTIONS
Definition: Controller.h:58
void motoRosAssert(BOOL mustBeTrue, ROS_ASSERTION_CODE subCodeIfFalse, char *msgFmtIfFalse,...)
Definition: Controller.c:951
int alarmCode
Definition: Controller.h:121
BOOL Ros_Controller_IsMotionReady(Controller *controller)
Definition: Controller.c:520
int tidIncMoveThread
Definition: Controller.h:140
IoStatusIndex
Definition: Controller.h:83
#define MAX_IO_CONNECTIONS
Definition: Controller.h:57
BOOL Ros_Controller_IsWaitingRos(Controller *controller)
Definition: Controller.c:515
BOOL Ros_Controller_StatusUpdate(Controller *controller)
Definition: Controller.c:695
int Ros_Controller_GetNotReadySubcode(Controller *controller)
Definition: Controller.c:558


motoman_driver
Author(s): Jeremy Zoss (Southwest Research Institute), Ted Miller (MotoROS) (Yaskawa Motoman), Eric Marcil (MotoROS) (Yaskawa Motoman)
autogenerated on Sat May 8 2021 02:27:43