Controller.c
Go to the documentation of this file.
1 // Controller.c
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 #include "MotoROS.h"
33 
34 extern STATUS setsockopt
35  (
36  int s, /* target socket */
37  int level, /* protocol level of option */
38  int optname, /* option name */
39  char * optval, /* pointer to option value */
40  int optlen /* option length */
41  );
42 
43 //-----------------------
44 // Function Declarations
45 //-----------------------
46 BOOL Ros_Controller_Init(Controller* controller);
48 BOOL Ros_Controller_IsValidGroupNo(Controller* controller, int groupNo);
49 int Ros_Controller_OpenSocket(int tcpPort);
51 // Status related
52 void Ros_Controller_StatusInit(Controller* controller);
53 BOOL Ros_Controller_IsAlarm(Controller* controller);
54 BOOL Ros_Controller_IsError(Controller* controller);
55 BOOL Ros_Controller_IsPlay(Controller* controller);
56 BOOL Ros_Controller_IsTeach(Controller* controller);
57 BOOL Ros_Controller_IsRemote(Controller* controller);
58 BOOL Ros_Controller_IsOperating(Controller* controller);
59 BOOL Ros_Controller_IsHold(Controller* controller);
60 BOOL Ros_Controller_IsServoOn(Controller* controller);
61 BOOL Ros_Controller_IsEStop(Controller* controller);
62 BOOL Ros_Controller_IsWaitingRos(Controller* controller);
64 int Ros_Controller_StatusToMsg(Controller* controller, SimpleMsg* sendMsg);
65 BOOL Ros_Controller_StatusRead(Controller* controller, USHORT ioStatus[IO_ROBOTSTATUS_MAX]);
66 BOOL Ros_Controller_StatusUpdate(Controller* controller);
67 // Wrapper around MPFunctions
68 BOOL Ros_Controller_GetIOState(ULONG signal);
69 void Ros_Controller_SetIOState(ULONG signal, BOOL status);
71 void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize);
72 
73 //-----------------------
74 // Function implementation
75 //-----------------------
76 
77 //Report version info to display on pendant (DX200 only)
79 {
80 #if DX100 || FS100
81  return;
82 #else
83  MP_APPINFO_SEND_DATA appInfoSendData;
84  MP_STD_RSP_DATA stdResponseData;
85 
86  sprintf(appInfoSendData.AppName, "MotoROS");
87 
88  sprintf(appInfoSendData.Version, "v%s", APPLICATION_VERSION);
89  sprintf(appInfoSendData.Comment, "Motoman ROS-I driver");
90 
91  mpApplicationInfoNotify(&appInfoSendData, &stdResponseData); //don't care about return value
92 #endif
93 }
94 
95 //-------------------------------------------------------------------
96 // Initialize the controller structure
97 // This should be done before the controller is used for anything
98 //-------------------------------------------------------------------
100 {
101  int grpNo;
102  int i;
103  BOOL bInitOk;
104  STATUS status;
105 
106  printf("Initializing controller\r\n");
107 
109 
110  // Turn off all I/O signal
119 
128 
129  // Init variables and controller status
130  bInitOk = TRUE;
131  controller->bRobotJobReady = FALSE;
132  controller->bStopMotion = FALSE;
133  controller->bPFLduringRosMove = FALSE;
134  Ros_Controller_StatusInit(controller);
135  Ros_Controller_StatusRead(controller, controller->ioStatus);
136 
137  // wait for controller to be ready for reading parameter
138  Ros_Controller_WaitInitReady(controller);
139 
140 #if (DX100)
141  // Determine if the robot is a DX100 SDA which requires a special case for the motion API
142  status = GP_isSdaRobot(&controller->bIsDx100Sda);
143  if (status != OK)
144  bInitOk = FALSE;
145 #endif
146 
147  // Get the interpolation clock
148  status = GP_getInterpolationPeriod(&controller->interpolPeriod);
149  if(status!=OK)
150  bInitOk = FALSE;
151 
152  // Get the number of groups
153  controller->numGroup = GP_getNumberOfGroups();
154 #ifdef DEBUG
155  printf("controller->numGroup = %d\n", controller->numGroup);
156 #endif
157  if(controller->numGroup < 1)
158  bInitOk = FALSE;
159 
160  if (controller->numGroup > MAX_CONTROLLABLE_GROUPS)
161  {
162  printf("!!!---Detected %d control groups. MotoROS will only control %d.---!!!\n", controller->numGroup, MAX_CONTROLLABLE_GROUPS);
163  controller->numGroup = MAX_CONTROLLABLE_GROUPS;
164  }
165 
166  controller->numRobot = 0;
167 
168  // Check for each group
169  for(grpNo=0; grpNo < MP_GRP_NUM; grpNo++)
170  {
171  if(grpNo < controller->numGroup)
172  {
173  // Determine if specific group exists and allocate memory for it
174  controller->ctrlGroups[grpNo] = Ros_CtrlGroup_Create(grpNo, //Zero based index of the group number(0 - 3)
175  (grpNo==(controller->numGroup-1)), //TRUE if this is the final group that is being initialized. FALSE if you plan to call this function again.
176  controller->interpolPeriod); //Value of the interpolation period (ms) for the robot controller.
177  if(controller->ctrlGroups[grpNo] != NULL)
178  {
179  Ros_CtrlGroup_GetPulsePosCmd(controller->ctrlGroups[grpNo], controller->ctrlGroups[grpNo]->prevPulsePos); // set the current commanded pulse
180  controller->numRobot++; //This counter is required for DX100 controllers with two control-groups (robot OR ext axis)
181  }
182  else
183  bInitOk = FALSE;
184  }
185  else
186  controller->ctrlGroups[grpNo] = NULL;
187  }
188 
189 #ifdef DEBUG
190  printf("controller->numRobot = %d\n", controller->numRobot);
191 #endif
192 
193  // Initialize Thread ID and Socket to invalid value
194  controller->tidConnectionSrv = INVALID_TASK;
195 
196  for (i = 0; i < MAX_IO_CONNECTIONS; i++)
197  {
198  controller->sdIoConnections[i] = INVALID_SOCKET;
199  controller->tidIoConnections[i] = INVALID_TASK;
200  }
201 
202  for (i = 0; i < MAX_STATE_CONNECTIONS; i++)
203  {
204  controller->sdStateConnections[i] = INVALID_SOCKET;
205  controller->tidStateSendState[i] = INVALID_TASK;
206  }
207 
208  for (i = 0; i < MAX_MOTION_CONNECTIONS; i++)
209  {
210  controller->sdMotionConnections[i] = INVALID_SOCKET;
211  controller->tidMotionConnections[i] = INVALID_TASK;
212  }
213  controller->tidIncMoveThread = INVALID_TASK;
214 
215 #ifdef DX100
216  controller->bSkillMotionReady[0] = FALSE;
217  controller->bSkillMotionReady[1] = FALSE;
218 #endif
219 
220  if(bInitOk)
221  {
222  // Turn on initialization done I/O signal
224  }
225  else
226  {
228  printf("Failure to initialize controller\r\n");
229  }
230 
231  return bInitOk;
232 }
233 
234 
235 //-------------------------------------------------------------------
236 // Wait for the controller to be ready to start initialization
237 //-------------------------------------------------------------------
239 {
240  do //minor alarms can be delayed briefly after bootup
241  {
242  puts("Waiting for robot alarms to clear...");
243  Ros_Sleep(2500);
244  Ros_Controller_StatusRead(controller, controller->ioStatus);
245 
246  }while(Ros_Controller_IsAlarm(controller));
247 
248  return TRUE;
249 }
250 
251 
252 //-------------------------------------------------------------------
253 // Check the number of inc_move currently in the specified queue
254 //-------------------------------------------------------------------
256 {
257  if((groupNo >= 0) && (groupNo < controller->numGroup))
258  return TRUE;
259  else
260  {
261  printf("ERROR: Attempt to access invalid Group No. (%d) \r\n", groupNo);
262  return FALSE;
263  }
264 }
265 
266 
267 //-------------------------------------------------------------------
268 // Open a socket to listen for incomming connection on specified port
269 // return: <0 : Error
270 // >=0 : socket descriptor
271 //-------------------------------------------------------------------
273 {
274  int sd; // socket descriptor
275  struct sockaddr_in serverSockAddr;
276  int ret;
277 
278  // Open the socket
279  sd = mpSocket(AF_INET, SOCK_STREAM, 0);
280  if (sd < 0)
281  return -1;
282 
283  // Set structure
284  memset(&serverSockAddr, 0, sizeof(struct sockaddr_in));
285  serverSockAddr.sin_family = AF_INET;
286  serverSockAddr.sin_addr.s_addr = INADDR_ANY;
287  serverSockAddr.sin_port = mpHtons(tcpPort);
288 
289  //bind to network interface
290  ret = mpBind(sd, (struct sockaddr *)&serverSockAddr, sizeof(struct sockaddr_in));
291  if (ret < 0)
292  goto closeSockHandle;
293 
294  //prepare to accept connections
295  ret = mpListen(sd, SOMAXCONN);
296  if (ret < 0)
297  goto closeSockHandle;
298 
299  return sd;
300 
301 closeSockHandle:
302  printf("Error in Ros_Controller_OpenSocket\r\n");
303 
304  if(sd >= 0)
305  mpClose(sd);
306 
307  return -2;
308 }
309 
310 
311 //-----------------------------------------------------------------------
312 // Main Connection Server Task that listens for new connections
313 //-----------------------------------------------------------------------
315 {
316  int sdMotionServer = INVALID_SOCKET;
317  int sdStateServer = INVALID_SOCKET;
318  int sdIoServer = INVALID_SOCKET;
319  int sdMax;
320  struct fd_set fds;
321  int sdAccepted = INVALID_SOCKET;
322  struct sockaddr_in clientSockAddr;
323  int sizeofSockAddr;
324  int useNoDelay = 1;
325  STATUS s;
326 
327  //Set feedback signal (Application is installed and running)
329 
330  printf("Controller connection server running\r\n");
331 
332  //New sockets for server listening to multiple port
333  sdMotionServer = Ros_Controller_OpenSocket(TCP_PORT_MOTION);
334  if(sdMotionServer < 0)
335  goto closeSockHandle;
336 
337  sdStateServer = Ros_Controller_OpenSocket(TCP_PORT_STATE);
338  if(sdStateServer < 0)
339  goto closeSockHandle;
340 
342  if(sdIoServer < 0)
343  goto closeSockHandle;
344 
345  sdMax = max(sdMotionServer, sdStateServer);
346  sdMax = max(sdMax, sdIoServer);
347 
348  FOREVER //Continue to accept multiple connections forever
349  {
350  FD_ZERO(&fds);
351  FD_SET(sdMotionServer, &fds);
352  FD_SET(sdStateServer, &fds);
353  FD_SET(sdIoServer, &fds);
354 
355  if(mpSelect(sdMax+1, &fds, NULL, NULL, NULL) > 0)
356  {
357  memset(&clientSockAddr, 0, sizeof(clientSockAddr));
358  sizeofSockAddr = sizeof(clientSockAddr);
359 
360  //Check motion server
361  if(FD_ISSET(sdMotionServer, &fds))
362  {
363  sdAccepted = mpAccept(sdMotionServer, (struct sockaddr *)&clientSockAddr, &sizeofSockAddr);
364  if (sdAccepted < 0)
365  break;
366 
367  s = setsockopt(sdAccepted, IPPROTO_TCP, TCP_NODELAY, (char*)&useNoDelay, sizeof (int));
368  if( OK != s )
369  {
370  printf("Failed to set TCP_NODELAY.\r\n");
371  }
372 
373  Ros_MotionServer_StartNewConnection(controller, sdAccepted);
374  }
375 
376  //Check state server
377  if(FD_ISSET(sdStateServer, &fds))
378  {
379  sdAccepted = mpAccept(sdStateServer, (struct sockaddr *)&clientSockAddr, &sizeofSockAddr);
380  if (sdAccepted < 0)
381  break;
382 
383  s = setsockopt(sdAccepted, IPPROTO_TCP, TCP_NODELAY, (char*)&useNoDelay, sizeof (int));
384  if( OK != s )
385  {
386  printf("Failed to set TCP_NODELAY.\r\n");
387  }
388 
389  Ros_StateServer_StartNewConnection(controller, sdAccepted);
390  }
391 
392  //Check IO server
393  if(FD_ISSET(sdIoServer, &fds))
394  {
395  sdAccepted = mpAccept(sdIoServer, (struct sockaddr *)&clientSockAddr, &sizeofSockAddr);
396  if (sdAccepted < 0)
397  break;
398 
399  s = setsockopt(sdAccepted, IPPROTO_TCP, TCP_NODELAY, (char*)&useNoDelay, sizeof (int));
400  if( OK != s )
401  {
402  printf("Failed to set TCP_NODELAY.\r\n");
403  }
404 
405  Ros_IoServer_StartNewConnection(controller, sdAccepted);
406  }
407  }
408  }
409 
410 closeSockHandle:
411  printf("Error!?... Connection Server is aborting. Reboot the controller.\r\n");
412 
413  if(sdIoServer >= 0)
414  mpClose(sdIoServer);
415  if(sdMotionServer >= 0)
416  mpClose(sdMotionServer);
417  if(sdStateServer >= 0)
418  mpClose(sdStateServer);
419 
420  //disable feedback signal
422 }
423 
424 
425 
426 /**** Controller Status functions ****/
427 
428 //-------------------------------------------------------------------
429 // Initialize list of Specific Input to keep track of
430 //-------------------------------------------------------------------
432 {
433  controller->ioStatusAddr[IO_ROBOTSTATUS_ALARM_MAJOR].ulAddr = 50010; // Alarm
434  controller->ioStatusAddr[IO_ROBOTSTATUS_ALARM_MINOR].ulAddr = 50011; // Alarm
435  controller->ioStatusAddr[IO_ROBOTSTATUS_ALARM_SYSTEM].ulAddr = 50012; // Alarm
436  controller->ioStatusAddr[IO_ROBOTSTATUS_ALARM_USER].ulAddr = 50013; // Alarm
437  controller->ioStatusAddr[IO_ROBOTSTATUS_ERROR].ulAddr = 50014; // Error
438  controller->ioStatusAddr[IO_ROBOTSTATUS_PLAY].ulAddr = 50054; // Play
439  controller->ioStatusAddr[IO_ROBOTSTATUS_TEACH].ulAddr = 50053; // Teach
440  controller->ioStatusAddr[IO_ROBOTSTATUS_REMOTE].ulAddr = 80011; //50056; // Remote // Modified E.M. 7/9/2013
441  controller->ioStatusAddr[IO_ROBOTSTATUS_OPERATING].ulAddr = 50070; // Operating
442  controller->ioStatusAddr[IO_ROBOTSTATUS_HOLD].ulAddr = 50071; // Hold
443  controller->ioStatusAddr[IO_ROBOTSTATUS_SERVO].ulAddr = 50073; // Servo ON
444  controller->ioStatusAddr[IO_ROBOTSTATUS_ESTOP_EX].ulAddr = 80025; // External E-Stop
445  controller->ioStatusAddr[IO_ROBOTSTATUS_ESTOP_PP].ulAddr = 80026; // Pendant E-Stop
446  controller->ioStatusAddr[IO_ROBOTSTATUS_ESTOP_CTRL].ulAddr = 80027; // Controller E-Stop
447  controller->ioStatusAddr[IO_ROBOTSTATUS_WAITING_ROS].ulAddr = IO_FEEDBACK_WAITING_MP_INCMOVE; // Job input signaling ready for external motion
448  controller->ioStatusAddr[IO_ROBOTSTATUS_INECOMODE].ulAddr = 50727; // Energy Saving Mode
449 #if (YRC1000||YRC1000u)
450  controller->ioStatusAddr[IO_ROBOTSTATUS_PFL_STOP].ulAddr = 81702; // PFL function stopped the motion
451  controller->ioStatusAddr[IO_ROBOTSTATUS_PFL_ESCAPE].ulAddr = 81703; // PFL function escape from clamping motion
452  controller->ioStatusAddr[IO_ROBOTSTATUS_PFL_AVOIDING].ulAddr = 15120; // PFL function avoidance operating
453  controller->ioStatusAddr[IO_ROBOTSTATUS_PFL_AVOID_JOINT].ulAddr = 15124; // PFL function avoidance joint enabled
454  controller->ioStatusAddr[IO_ROBOTSTATUS_PFL_AVOID_TRANS].ulAddr = 15125; // PFL function avoidance translation enabled
455 #endif
456  controller->alarmCode = 0;
457 }
458 
459 
461 {
462  return ((controller->ioStatus[IO_ROBOTSTATUS_ALARM_MAJOR]!=0)
463  || (controller->ioStatus[IO_ROBOTSTATUS_ALARM_MINOR]!=0)
464  || (controller->ioStatus[IO_ROBOTSTATUS_ALARM_SYSTEM]!=0)
465  || (controller->ioStatus[IO_ROBOTSTATUS_ALARM_USER]!=0) );
466 }
467 
469 {
470  return ((controller->ioStatus[IO_ROBOTSTATUS_ERROR]!=0));
471 }
472 
474 {
475  return ((controller->ioStatus[IO_ROBOTSTATUS_PLAY]!=0));
476 }
477 
479 {
480  return ((controller->ioStatus[IO_ROBOTSTATUS_TEACH]!=0));
481 }
482 
484 {
485  return ((controller->ioStatus[IO_ROBOTSTATUS_REMOTE]!=0));
486 }
487 
489 {
490  return ((controller->ioStatus[IO_ROBOTSTATUS_OPERATING]!=0));
491 }
492 
494 {
495  return ((controller->ioStatus[IO_ROBOTSTATUS_HOLD]!=0));
496 }
497 
499 {
500  return ((controller->ioStatus[IO_ROBOTSTATUS_SERVO] != 0) && (controller->ioStatus[IO_ROBOTSTATUS_INECOMODE] == 0));
501 }
502 
504 {
505  return (controller->ioStatus[IO_ROBOTSTATUS_INECOMODE] != 0);
506 }
507 
509 {
510  return ((controller->ioStatus[IO_ROBOTSTATUS_ESTOP_EX]==0)
511  || (controller->ioStatus[IO_ROBOTSTATUS_ESTOP_PP]==0)
512  || (controller->ioStatus[IO_ROBOTSTATUS_ESTOP_CTRL]==0) );
513 }
514 
516 {
517  return ((controller->ioStatus[IO_ROBOTSTATUS_WAITING_ROS]!=0));
518 }
519 
521 {
522  BOOL bMotionReady;
523 
524 #ifndef DUMMY_SERVO_MODE
525  bMotionReady = controller->bRobotJobReady && Ros_Controller_IsOperating(controller) && Ros_Controller_IsRemote(controller)
526  && !Ros_Controller_IsPflActive(controller);
527 #else
528  bMotionReady = controller->bRobotJobReady && Ros_Controller_IsOperating(controller);
529 #endif
530 
531 
532 #ifdef DX100
533  if(controller->numRobot < 2)
534  bMotionReady = bMotionReady && controller->bSkillMotionReady[0];
535  else
536  bMotionReady = bMotionReady && controller->bSkillMotionReady[0] && controller->bSkillMotionReady[1];
537 #endif
538 
539  return bMotionReady;
540 }
541 
542 
544 {
545 #if (YRC1000||YRC1000u)
546  //return ((controller->ioStatus[IO_ROBOTSTATUS_PFL_STOP] | controller->ioStatus[IO_ROBOTSTATUS_PFL_ESCAPE]) != 0);
547  if (controller->bPFLduringRosMove || controller->ioStatus[IO_ROBOTSTATUS_PFL_STOP] || controller->ioStatus[IO_ROBOTSTATUS_PFL_ESCAPE] ||
548  ( controller->ioStatus[IO_ROBOTSTATUS_PFL_AVOIDING]
549  && (controller->ioStatus[IO_ROBOTSTATUS_PFL_AVOID_JOINT] || controller->ioStatus[IO_ROBOTSTATUS_PFL_AVOID_TRANS])) != 0)
550  {
551  return TRUE;
552  }
553 #endif
554  return FALSE;
555 }
556 
557 
559 {
560  // Check alarm
561  if(Ros_Controller_IsAlarm(controller))
563 
564  // Check error
565  if(Ros_Controller_IsError(controller))
567 
568  // Check e-stop
569  if(Ros_Controller_IsEStop(controller))
571 
572  // Check play mode
573  if(!Ros_Controller_IsPlay(controller))
575 
576 #ifndef DUMMY_SERVO_MODE
577  // Check remote
578  if(!Ros_Controller_IsRemote(controller))
580 
581  // Check servo power
582  if(!Ros_Controller_IsServoOn(controller))
584 #endif
585 
586  // Check hold
587  if(Ros_Controller_IsHold(controller))
589 
590  // Check PFL active
591  if (Ros_Controller_IsPflActive(controller))
593 
594  // Check operating
595  if(!Ros_Controller_IsOperating(controller))
597 
598  // Check ready I/O signal (should confirm wait)
599  if(!Ros_Controller_IsWaitingRos(controller))
601 
602  // Check skill send command
603  if(!Ros_Controller_IsMotionReady(controller))
605 
607 }
608 
610 {
611  int i;
612  int groupNo;
613  long fbPulsePos[MAX_PULSE_AXES];
614  long cmdPulsePos[MAX_PULSE_AXES];
615  BOOL bDataInQ;
616  CtrlGroup* ctrlGroup;
617 
618  bDataInQ = Ros_MotionServer_HasDataInQueue(controller);
619 
620  if (bDataInQ == TRUE)
621  return TRUE;
622  else if (bDataInQ == ERROR)
623  return ERROR;
624  else
625  {
626  //for each control group
627  for (groupNo = 0; groupNo < controller->numGroup; groupNo++)
628  {
629  //Check group number valid
630  if (!Ros_Controller_IsValidGroupNo(controller, groupNo))
631  continue;
632 
633  //Check if the feeback position has caught up to the command position
634  ctrlGroup = controller->ctrlGroups[groupNo];
635 
636  Ros_CtrlGroup_GetFBPulsePos(ctrlGroup, fbPulsePos);
637  Ros_CtrlGroup_GetPulsePosCmd(ctrlGroup, cmdPulsePos);
638 
639  for (i = 0; i < MP_GRP_AXES_NUM; i += 1)
640  {
641  if (ctrlGroup->axisType.type[i] != AXIS_INVALID)
642  {
643  // Check if position matches current command position
644  if (abs(fbPulsePos[i] - cmdPulsePos[i]) > START_MAX_PULSE_DEVIATION)
645  return TRUE;
646  }
647  }
648  }
649  }
650 
651  return FALSE;
652 }
653 
654 // Creates a simple message of type: ROS_MSG_ROBOT_STATUS = 13
655 // Simple message containing the current state of the controller
657 {
658  //initialize memory
659  memset(sendMsg, 0x00, sizeof(SimpleMsg));
660 
661  // set prefix: length of message excluding the prefix
662  sendMsg->prefix.length = sizeof(SmHeader) + sizeof(SmBodyRobotStatus);
663 
664  // set header information
666  sendMsg->header.commType = ROS_COMM_TOPIC;
668 
669  // set body
670  sendMsg->body.robotStatus.drives_powered = (int)(Ros_Controller_IsServoOn(controller));
671  sendMsg->body.robotStatus.e_stopped = (int)(Ros_Controller_IsEStop(controller));
672  sendMsg->body.robotStatus.error_code = controller->alarmCode;
673  sendMsg->body.robotStatus.in_error = (int)Ros_Controller_IsAlarm(controller);
674  sendMsg->body.robotStatus.in_motion = (int)(Ros_Controller_IsInMotion(controller));
675  if(Ros_Controller_IsPlay(controller))
676  sendMsg->body.robotStatus.mode = 2;
677  else
678  sendMsg->body.robotStatus.mode = 1;
679  sendMsg->body.robotStatus.motion_possible = (int)(Ros_Controller_IsMotionReady(controller));
680 
681  return(sendMsg->prefix.length + sizeof(SmPrefix));
682 }
683 
684 //-------------------------------------------------------------------
685 // Get I/O state on the controller
686 //-------------------------------------------------------------------
687 BOOL Ros_Controller_StatusRead(Controller* controller, USHORT ioStatus[IO_ROBOTSTATUS_MAX])
688 {
689  return (mpReadIO(controller->ioStatusAddr, ioStatus, IO_ROBOTSTATUS_MAX) == 0);
690 }
691 
692 //-------------------------------------------------------------------
693 // Update I/O state on the controller
694 //-------------------------------------------------------------------
696 {
697  USHORT ioStatus[IO_ROBOTSTATUS_MAX];
698  int i;
699  BOOL prevReadyStatus;
700 
701  prevReadyStatus = Ros_Controller_IsMotionReady(controller);
702 
703  if(Ros_Controller_StatusRead(controller, ioStatus))
704  {
705  // Check for change of state and potentially react to the change
706  for(i=0; i<IO_ROBOTSTATUS_MAX; i++)
707  {
708  if(controller->ioStatus[i] != ioStatus[i])
709  {
710  //printf("Change of ioStatus[%d]\r\n", i);
711 
712  controller->ioStatus[i] = ioStatus[i];
713  switch(i)
714  {
715  case IO_ROBOTSTATUS_ALARM_MAJOR: // alarm
716  case IO_ROBOTSTATUS_ALARM_MINOR: // alarm
717  case IO_ROBOTSTATUS_ALARM_SYSTEM: // alarm
718  case IO_ROBOTSTATUS_ALARM_USER: // alarm
719  {
720  if(ioStatus[IO_ROBOTSTATUS_ALARM_USER] == 0)
721  controller->alarmCode = 0;
722  else
723  controller->alarmCode = Ros_Controller_GetAlarmCode();
724 
725  break;
726  }
727 
728  case IO_ROBOTSTATUS_WAITING_ROS: // Job input signaling ready for external motion
729  {
730  if(ioStatus[IO_ROBOTSTATUS_WAITING_ROS] == 0) // signal turned OFF
731  {
732  // Job execution stopped take action
733  controller->bRobotJobReady = FALSE;
734  Ros_MotionServer_ClearQ_All(controller);
735  }
736  else // signal turned ON (rising edge)
737  controller->bRobotJobReady = TRUE; //job is ready (even if other factors will prevent motion)
738  break;
739  }
740 #if (YRC1000||YRC1000u)
741  case IO_ROBOTSTATUS_PFL_STOP: // PFL Stop
742  case IO_ROBOTSTATUS_PFL_ESCAPE: // PFL Escaping
743  case IO_ROBOTSTATUS_PFL_AVOIDING: // PFL Avoidance
744  {
745  if (controller->bRobotJobReady && Ros_Controller_IsPflActive(controller))
746  {
747  // Job execution stopped by PFL take action
748  controller->bPFLduringRosMove = TRUE; //force job to be restarted with new ROS_CMD_START_TRAJ_MODE command
749  Ros_MotionServer_ClearQ_All(controller);
750  }
751  break;
752  }
753 #endif
754  }
755  }
756  }
757 
758  if (!prevReadyStatus && Ros_Controller_IsMotionReady(controller))
759  printf("Robot job is ready for ROS commands.\r\n");
760 
761  return TRUE;
762  }
763  else
764  return FALSE;
765 }
766 
767 
768 
769 /**** Wrappers on MP standard function ****/
770 
771 //-------------------------------------------------------------------
772 // Get I/O state on the controller
773 //-------------------------------------------------------------------
774 BOOL Ros_Controller_GetIOState(ULONG signal)
775 {
776  MP_IO_INFO ioInfo;
777  USHORT ioState;
778  int ret;
779 
780  //set feedback signal
781  ioInfo.ulAddr = signal;
782  ret = mpReadIO(&ioInfo, &ioState, 1);
783  if(ret != 0)
784  printf("mpReadIO failure (%d)\r\n", ret);
785 
786  return (ioState != 0);
787 }
788 
789 
790 //-------------------------------------------------------------------
791 // Set I/O state on the controller
792 //-------------------------------------------------------------------
793 void Ros_Controller_SetIOState(ULONG signal, BOOL status)
794 {
795  MP_IO_DATA ioData;
796  int ret;
797 
798  //set feedback signal
799  ioData.ulAddr = signal;
800  ioData.ulValue = status;
801  ret = mpWriteIO(&ioData, 1);
802  if(ret != 0)
803  printf("mpWriteIO failure (%d)\r\n", ret);
804 }
805 
806 
807 //-------------------------------------------------------------------
808 // Get the code of the first alarm on the controller
809 //-------------------------------------------------------------------
811 {
812  MP_ALARM_CODE_RSP_DATA alarmData;
813  memset(&alarmData, 0x00, sizeof(alarmData));
814  if(mpGetAlarmCode(&alarmData) == 0)
815  {
816  if(alarmData.usAlarmNum > 0)
817  return(alarmData.AlarmData.usAlarmNo[0]);
818  else
819  return 0;
820  }
821  return -1;
822 }
823 
824 
825 //-------------------------------------------------------------------
826 // Convert error code to string
827 //-------------------------------------------------------------------
828 void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize)
829 {
830  switch(errNo)
831  {
832  case 0x2010: memcpy(errMsg, "Robot is in operation", errMsgSize); break;
833  case 0x2030: memcpy(errMsg, "In HOLD status (PP)", errMsgSize); break;
834  case 0x2040: memcpy(errMsg, "In HOLD status (External)", errMsgSize); break;
835  case 0x2050: memcpy(errMsg, "In HOLD status (Command)", errMsgSize); break;
836  case 0x2060: memcpy(errMsg, "In ERROR/ALARM status", errMsgSize); break;
837  case 0x2070: memcpy(errMsg, "In SERVO OFF status", errMsgSize); break;
838  case 0x2080: memcpy(errMsg, "Wrong operation mode", errMsgSize); break;
839  case 0x3040: memcpy(errMsg, "The home position is not registered", errMsgSize); break;
840  case 0x3050: memcpy(errMsg, "Out of range (ABSO data", errMsgSize); break;
841  case 0x3400: memcpy(errMsg, "Cannot operate MASTER JOB", errMsgSize); break;
842  case 0x3410: memcpy(errMsg, "The JOB name is already registered in another task", errMsgSize); break;
843  case 0x4040: memcpy(errMsg, "Specified JOB not found", errMsgSize); break;
844  case 0x5200: memcpy(errMsg, "Over data range", errMsgSize); break;
845  default: memcpy(errMsg, "Unspecified reason", errMsgSize); break;
846  }
847 }
848 
849 
850 #ifdef DX100
851 
852 void Ros_Controller_ListenForSkill(Controller* controller, int sl)
853 {
854  SYS2MP_SENS_MSG skillMsg;
855  STATUS apiRet;
856 
857  controller->bSkillMotionReady[sl - MP_SL_ID1] = FALSE;
858  memset(&skillMsg, 0x00, sizeof(SYS2MP_SENS_MSG));
859 
860  FOREVER
861  {
862  //SKILL complete
863  //This will cause the SKILLSND command to complete the cursor to move to the next line.
864  //Make sure all preparation is complete to move.
865  //mpEndSkillCommandProcess(sl, &skillMsg);
866  mpEndSkillCommandProcess(sl, &skillMsg);
867 
868  Ros_Sleep(4); //sleepy time
869 
870  //Get SKILL command
871  //task will wait for a skillsnd command in INFORM
872  apiRet = mpReceiveSkillCommand(sl, &skillMsg);
873 
874  if (skillMsg.main_comm != MP_SKILL_COMM)
875  {
876  printf("Ignoring command, because it's not a SKILL command\n");
877  continue;
878  }
879 
880  //Process SKILL command
881  switch(skillMsg.sub_comm)
882  {
883  case MP_SKILL_SEND:
884  if(strcmp(skillMsg.cmd, "ROS-START") == 0)
885  {
886  controller->bSkillMotionReady[sl - MP_SL_ID1] = TRUE;
887  }
888  else if(strcmp(skillMsg.cmd, "ROS-STOP") == 0)
889  {
890  controller->bSkillMotionReady[sl - MP_SL_ID1] = FALSE;
891  }
892  else
893  {
894  printf ("MP_SKILL_SEND(SL_ID=%d) - %s \n", sl, skillMsg.cmd);
895  }
896 #ifdef DEBUG
897  printf("controller->bSkillMotionReady[%d] = %d\n", (sl - MP_SL_ID1), controller->bSkillMotionReady[sl - MP_SL_ID1]);
898 #endif
899 
900  if(Ros_Controller_IsMotionReady(controller))
901  printf("Robot job is ready for ROS commands.\r\n");
902  break;
903 
904  case MP_SKILL_END:
905  //ABORT!!!
906  controller->bSkillMotionReady[sl - MP_SL_ID1] = FALSE;
907  break;
908  }
909  }
910 }
911 #endif
912 
913 
914 #if DX100
915 // VxWorks 5.5 do not have vsnprintf, use vsprintf instead...
916 int vsnprintf(char *s, size_t sz, const char *fmt, va_list args)
917 {
918  char tmpBuf[1024]; // Hopefully enough...
919  size_t res;
920  res = vsprintf(tmpBuf, fmt, args);
921  tmpBuf[sizeof(tmpBuf) - 1] = 0; // be sure ending \0 is there
922  if (res >= sz)
923  {
924  // Buffer overrun...
925  printf("Logging.. Error vsnprintf:%d max:%d, anyway:\r\n", (int)res, (int)sz);
926  printf("%s", tmpBuf);
927  res = -res;
928  }
929  strncpy(s, tmpBuf, sz);
930  s[sz - 1] = 0; // be sure ending \0 is there
931  return res;
932 }
933 
934 // VxWorks 5.5 do not have snprintf
935 int snprintf(char *s, size_t sz, const char *fmt, ...)
936 {
937  size_t res;
938  char tmpBuf[1024]; // Hopefully enough...
939  va_list va;
940 
941  va_start(va, fmt);
942  res = vsnprintf(tmpBuf, sz, fmt, va);
943  va_end(va);
944 
945  strncpy(s, tmpBuf, sz);
946  s[sz - 1] = 0; // be sure ending \0 is there
947  return res;
948 }
949 #endif
950 
951 void motoRosAssert(BOOL mustBeTrue, ROS_ASSERTION_CODE subCodeIfFalse, char* msgFmtIfFalse, ...)
952 {
953  const int MAX_MSG_LEN = 32;
954  char msg[MAX_MSG_LEN];
955  char subMsg[MAX_MSG_LEN];
956  va_list va;
957 
958  if (!mustBeTrue)
959  {
960  memset(msg, 0x00, MAX_MSG_LEN);
961  memset(subMsg, 0x00, MAX_MSG_LEN);
962 
963  va_start(va, msgFmtIfFalse);
964  vsnprintf(subMsg, MAX_MSG_LEN, msgFmtIfFalse, va);
965  va_end(va);
966 
967  snprintf(msg, MAX_MSG_LEN, "MotoROS:%s", subMsg); //add "MotoROS" to distinguish from other controller alarms
968 
971 
972  mpSetAlarm(8000, msg, subCodeIfFalse);
973 
974  while (TRUE) //forever
975  {
976  puts(msg);
977  Ros_Sleep(5000);
978  }
979  }
980 }
981 
982 void Db_Print(char* msgFormat, ...)
983 {
984 #ifdef DEBUG
985  const int MAX_MSG_LEN = 128;
986  char msg[MAX_MSG_LEN];
987  va_list va;
988 
989  memset(msg, 0x00, MAX_MSG_LEN);
990 
991  va_start(va, msgFormat);
992  vsnprintf(msg, MAX_MSG_LEN, msgFormat, va);
993  va_end(va);
994 
995  printf(msg);
996 #endif
997 }
998 
999 void Ros_Sleep(float milliseconds)
1000 {
1001  mpTaskDelay(milliseconds / mpGetRtc()); //Tick length varies between controller models
1002 }
void Ros_Controller_SetIOState(ULONG signal, BOOL status)
Definition: Controller.c:793
SmMsgType msgType
int tidStateSendState[MAX_STATE_CONNECTIONS]
Definition: Controller.h:134
#define IO_FEEDBACK_CONNECTSERVERRUNNING
Definition: Controller.h:42
#define IO_FEEDBACK_WAITING_MP_INCMOVE
Definition: Controller.h:39
BOOL Ros_Controller_Init(Controller *controller)
Definition: Controller.c:99
int sdIoConnections[MAX_IO_CONNECTIONS]
Definition: Controller.h:130
void Ros_Controller_ErrNo_ToString(int errNo, char errMsg[ERROR_MSG_MAX_SIZE], int errMsgSize)
Definition: Controller.c:828
AXIS_TYPE type[MAX_PULSE_AXES]
BOOL bStopMotion
Definition: Controller.h:123
BOOL Ros_Controller_IsHold(Controller *controller)
Definition: Controller.c:493
#define INVALID_TASK
Definition: Controller.h:68
#define MAX_CONTROLLABLE_GROUPS
Definition: Controller.h:64
int tidConnectionSrv
Definition: Controller.h:127
BOOL Ros_CtrlGroup_GetPulsePosCmd(CtrlGroup *ctrlGroup, long pulsePos[MAX_PULSE_AXES])
Definition: CtrlGroup.c:212
#define IO_FEEDBACK_FAILURE
Definition: Controller.h:46
BOOL Ros_Controller_IsOperating(Controller *controller)
Definition: Controller.c:488
#define TCP_PORT_MOTION
Definition: Controller.h:35
BOOL Ros_Controller_IsServoOn(Controller *controller)
Definition: Controller.c:498
struct _SmHeader SmHeader
XmlRpcServer s
void reportVersionInfoToController()
Definition: Controller.c:78
#define IO_FEEDBACK_RESERVED_6
Definition: Controller.h:53
BOOL Ros_Controller_IsPlay(Controller *controller)
Definition: Controller.c:473
void Ros_Controller_ConnectionServer_Start(Controller *controller)
Definition: Controller.c:314
SmPrefix prefix
#define APPLICATION_VERSION
Definition: MotoROS.h:35
#define START_MAX_PULSE_DEVIATION
Definition: Controller.h:76
void Ros_IoServer_StartNewConnection(Controller *controller, int sd)
Definition: IoServer.c:45
int groupNo
#define IO_FEEDBACK_RESERVED_5
Definition: Controller.h:52
int numRobot
Definition: Controller.h:115
CtrlGroup * ctrlGroups[MP_GRP_NUM]
Definition: Controller.h:116
#define ERROR_MSG_MAX_SIZE
Definition: Controller.h:74
BOOL Ros_CtrlGroup_GetFBPulsePos(CtrlGroup *ctrlGroup, long pulsePos[MAX_PULSE_AXES])
Definition: CtrlGroup.c:271
#define IO_FEEDBACK_RESERVED_1
Definition: Controller.h:48
long prevPulsePos[MAX_PULSE_AXES]
Definition: CtrlGroup.h:100
#define MAX_STATE_CONNECTIONS
Definition: Controller.h:59
STATUS GP_isSdaRobot(BOOL *bIsSda)
BOOL bPFLduringRosMove
Definition: Controller.h:124
void Db_Print(char *msgFormat,...)
Definition: Controller.c:982
STATUS GP_getInterpolationPeriod(UINT16 *periodInMilliseconds)
#define IO_FEEDBACK_RESERVED_4
Definition: Controller.h:51
BOOL Ros_Controller_IsTeach(Controller *controller)
Definition: Controller.c:478
#define TCP_PORT_STATE
Definition: Controller.h:36
int sdMotionConnections[MAX_MOTION_CONNECTIONS]
Definition: Controller.h:138
void Ros_Controller_StatusInit(Controller *controller)
Definition: Controller.c:431
#define IO_FEEDBACK_MOTIONSERVERCONNECTED
Definition: Controller.h:43
SmBodyRobotStatus robotStatus
#define IO_FEEDBACK_RESERVED_8
Definition: Controller.h:55
int tidMotionConnections[MAX_MOTION_CONNECTIONS]
Definition: Controller.h:139
BOOL Ros_Controller_StatusRead(Controller *controller, USHORT ioStatus[IO_ROBOTSTATUS_MAX])
Definition: Controller.c:687
STATUS
void Ros_Sleep(float milliseconds)
Definition: Controller.c:999
ROS_ASSERTION_CODE
Definition: Controller.h:181
int Ros_Controller_OpenSocket(int tcpPort)
Definition: Controller.c:272
#define IO_FEEDBACK_RESERVED_3
Definition: Controller.h:50
BOOL Ros_Controller_IsEcoMode(Controller *controller)
Definition: Controller.c:503
int sdStateConnections[MAX_STATE_CONNECTIONS]
Definition: Controller.h:135
STATUS setsockopt(int s, int level, int optname, char *optval, int optlen)
int GP_getNumberOfGroups()
int Ros_Controller_StatusToMsg(Controller *controller, SimpleMsg *sendMsg)
Definition: Controller.c:656
#define IO_FEEDBACK_MP_INCMOVE_DONE
Definition: Controller.h:40
SmHeader header
BOOL bRobotJobReady
Definition: Controller.h:122
#define IO_FEEDBACK_INITIALIZATION_DONE
Definition: Controller.h:41
void motoRosAssert(BOOL mustBeTrue, ROS_ASSERTION_CODE subCodeIfFalse, char *msgFmtIfFalse,...)
Definition: Controller.c:951
BOOL Ros_Controller_IsValidGroupNo(Controller *controller, int groupNo)
Definition: Controller.c:255
BOOL Ros_Controller_IsAlarm(Controller *controller)
Definition: Controller.c:460
#define IO_FEEDBACK_STATESERVERCONNECTED
Definition: Controller.h:44
int numGroup
Definition: Controller.h:114
BOOL Ros_Controller_IsRemote(Controller *controller)
Definition: Controller.c:483
SmReplyType replyType
BOOL Ros_Controller_IsPflActive(Controller *controller)
Definition: Controller.c:543
#define IO_FEEDBACK_RESERVED_7
Definition: Controller.h:54
SmCommType commType
#define IO_FEEDBACK_IOSERVERCONNECTED
Definition: Controller.h:45
UINT16 interpolPeriod
Definition: Controller.h:113
BOOL Ros_Controller_GetIOState(ULONG signal)
Definition: Controller.c:774
BOOL Ros_Controller_StatusUpdate(Controller *controller)
Definition: Controller.c:695
#define INVALID_SOCKET
Definition: Controller.h:67
BOOL Ros_MotionServer_HasDataInQueue(Controller *controller)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
#define TCP_PORT_IO
Definition: Controller.h:37
#define MAX_MOTION_CONNECTIONS
Definition: Controller.h:58
int tidIoConnections[MAX_IO_CONNECTIONS]
Definition: Controller.h:131
#define IO_FEEDBACK_RESERVED_2
Definition: Controller.h:49
BOOL Ros_Controller_IsMotionReady(Controller *controller)
Definition: Controller.c:520
BOOL Ros_Controller_IsEStop(Controller *controller)
Definition: Controller.c:508
#define IPPROTO_TCP
Definition: Controller.h:71
int Ros_Controller_GetNotReadySubcode(Controller *controller)
Definition: Controller.c:558
int alarmCode
Definition: Controller.h:121
int tidIncMoveThread
Definition: Controller.h:140
BOOL Ros_Controller_IsWaitingRos(Controller *controller)
Definition: Controller.c:515
BOOL Ros_Controller_IsError(Controller *controller)
Definition: Controller.c:468
MP_IO_INFO ioStatusAddr[IO_ROBOTSTATUS_MAX]
Definition: Controller.h:119
double max(double a, double b)
#define MAX_IO_CONNECTIONS
Definition: Controller.h:57
USHORT ioStatus[IO_ROBOTSTATUS_MAX]
Definition: Controller.h:120
void Ros_MotionServer_StartNewConnection(Controller *controller, int sd)
Definition: MotionServer.c:82
BOOL Ros_Controller_WaitInitReady(Controller *controller)
Definition: Controller.c:238
AXIS_MOTION_TYPE axisType
Definition: CtrlGroup.h:101
CtrlGroup * Ros_CtrlGroup_Create(int groupNo, BOOL bIsLastGrpToInit, float interpolPeriod)
Definition: CtrlGroup.c:59
int Ros_Controller_GetAlarmCode()
Definition: Controller.c:810
void Ros_StateServer_StartNewConnection(Controller *controller, int sd)
Definition: StateServer.c:49
BOOL Ros_Controller_IsInMotion(Controller *controller)
Definition: Controller.c:609
BOOL Ros_MotionServer_ClearQ_All(Controller *controller)


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