CtrlGroup.h
Go to the documentation of this file.
00001 // CtrlGroup.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 CTRLGROUP_H
00033 #define CTRLGROUP_H
00034 
00035 
00036 #define Q_SIZE 200
00037 
00038 #if (DX100 || DX200 || FS100)
00039 #define Q_LOCK_TIMEOUT 1000
00040 #else
00041 #define Q_LOCK_TIMEOUT 5000  //YRC1000 tick period is 0.2 ms
00042 #endif
00043 
00044 #define Q_OFFSET_IDX( a, b, c ) (((a)+(b)) >= (c) ) ? ((a)+(b)-(c)) \
00045                                 : ( (((a)+(b)) < 0 ) ? ((a)+(b)+(c)) : ((a)+(b)) )
00046                 
00047 #define RAD_PER_DEGREE (0.0174533)
00048 
00049 typedef struct
00050 {
00051         LONG time;
00052         UCHAR frame;
00053         UCHAR user;
00054         UCHAR tool;
00055         LONG inc[MP_GRP_AXES_NUM];
00056 } Incremental_data;
00057 
00058 typedef struct
00059 {
00060         SEM_ID q_lock;
00061         LONG cnt;
00062         LONG idx;
00063         Incremental_data data[Q_SIZE];
00064 } Incremental_q;
00065 
00066 // jointMotionData values are in radian and joint order in sequential order 
00067 typedef struct
00068 {
00069         int flag;
00070         int time;                                               // time in millisecond
00071         float pos[MP_GRP_AXES_NUM];             // position in radians
00072         float vel[MP_GRP_AXES_NUM];             // velocity in radians/s
00073         float acc[MP_GRP_AXES_NUM];             // acceleration in radians/s^2
00074 } JointMotionData;
00075 
00076 //---------------------------------------------------------------
00077 // CtrlGroup:
00078 // Structure containing all the data related to a control group 
00079 //---------------------------------------------------------------
00080 typedef struct 
00081 {
00082         int groupNo;                                                            // sequence group number
00083         int numAxes;                                                            // number of axis in the control group
00084         MP_GRP_ID_TYPE groupId;                                         // control group ID
00085         PULSE_TO_RAD pulseToRad;                                        // conversion ratio between pulse and radian
00086         PULSE_TO_METER pulseToMeter;                            // conversion ratio between pulse and meter (linear axis)
00087         FB_PULSE_CORRECTION_DATA correctionData;        // compensation for axes coupling
00088         MAX_INCREMENT_INFO maxInc;                                      // maximum increment per interpolation cycle
00089         float maxSpeed[MP_GRP_AXES_NUM];                        // maximum joint speed in radian/sec (rotational) or meter/sec (linear)
00090         
00091         Incremental_q inc_q;                                            // incremental queue
00092         long q_time;                                                            // time to which the queue has been processed
00093         
00094         JointMotionData jointMotionData;                        // joint motion command data in radian
00095         JointMotionData jointMotionDataToProcess;       // joint motion command data in radian to process
00096         BOOL hasDataToProcess;                                          // indicates that there is data to process
00097         int tidAddToIncQueue;                                           // ThreadId to add incremental values to the queue
00098         int timeLeftover_ms;                                            // Time left over after reaching the end of a trajectory to complete the interpolation period
00099         long prevPulsePos[MAX_PULSE_AXES];                      // The commanded pulse position that the trajectory starts at (Ros_MotionServer_StartTrajMode)
00100         AXIS_MOTION_TYPE axisType;                                      // Indicates whether axis is rotary or linear
00101 
00102         BOOL bIsBaxisSlave;                                                     // Indicates the B axis will automatically move to maintain orientation as other axes are moved
00103 
00104         JOINT_FEEDBACK_SPEED_ADDRESSES speedFeedbackRegisterAddress; //CIO address for the registers containing feedback speed
00105 } CtrlGroup;
00106 
00107 
00108 //---------------------------------
00109 // External Functions Declaration
00110 //---------------------------------
00111 
00112 //Initialize specific control group. This should be called for each group connected to the robot
00113 //controller in numerical order.
00114 //      int groupNo: Zero based index of the group number (0-3)
00115 //      BOOL bIsLastGrpToInit: TRUE if this is the final group that is being initialized. FALSE if you plan to call this function again.
00116 //      float interpolPeriod: Value of the interpolation period (ms) for the robot controller.
00117 extern CtrlGroup* Ros_CtrlGroup_Create(int groupNo, BOOL bIsLastGrpToInit, float interpolPeriod);
00118 
00119 extern BOOL Ros_CtrlGroup_GetPulsePosCmd(CtrlGroup* ctrlGroup, long pulsePos[MAX_PULSE_AXES]);
00120 extern BOOL Ros_CtrlGroup_GetFBPulsePos(CtrlGroup* ctrlGroup, long pulsePos[MAX_PULSE_AXES]);
00121 extern BOOL Ros_CtrlGroup_GetFBServoSpeed(CtrlGroup* ctrlGroup, long pulseSpeed[MAX_PULSE_AXES]);
00122 
00123 extern BOOL Ros_CtrlGroup_GetTorque(CtrlGroup* ctrlGroup, double torqueValues[MAX_PULSE_AXES]);
00124 
00125 extern void Ros_CtrlGroup_ConvertToRosPos(CtrlGroup* ctrlGroup, long pulsePos[MAX_PULSE_AXES], float rosPos[MAX_PULSE_AXES]);
00126 extern void Ros_CtrlGroup_ConvertToMotoPos(CtrlGroup* ctrlGroup, float radPos[MAX_PULSE_AXES], long pulsePos[MAX_PULSE_AXES]);
00127 
00128 extern UCHAR Ros_CtrlGroup_GetAxisConfig(CtrlGroup* ctrlGroup);
00129 
00130 extern BOOL Ros_CtrlGroup_IsRobot(CtrlGroup* ctrlGroup);
00131 
00132 #endif


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