Matlab script for RAPID equivalent commands please note that variables should be declared as global as in RAPID syntaxis this script demonstrates the use of functions in the matlab script. This script can be translated to RAPID by means of the matlab2RAPID script. IN ORDER TO SIMULATE THE PROGRAM: A) FIRST, LOAD A ROBOT robot = load_robot('abb','irb140'); OR robot = load_robot('abb','irb52'); B) NEXT, LOAD SOME EQUIPMENT. robot.equipment = load_robot('equipment','tables/table_two_areas'); C) NOW, LOAD AN END TOOL robot.tool= load_robot('equipment','end_tools/parallel_gripper_0'); D) FINALLY, LOAD A PIECE TO GRAB BY THE ROBOT robot.piece=load_robot('equipment','cylinders/cylinder_tiny'); E) IF NECESSARY, CHANGE THE POSITION AND ORIENTATION OF THE piece, relative to the robot's base reference system. robot.piece.T0= [1 0 0 -0.1; 0 1 0 -0.5; 0 0 1 0.2; 0 0 0 1]; during the simulation, call simulation_open_tool; to open the tool and simulation_close_tool; to close it. To grip the piece, call simulation_grip_piece; and simulation_release_piece to release it. The call to each function must be in a correct, otherwise, the result may be undesired, thus, typically the correct sequence is: simulation_open_tool; (approach the piece to grab with MoveL or MoveJ) simulation_close_tool; simulation_grip_piece; --> the piece will be drawn with the robot move to a different place with MoveJ or MoveL simulation_open_tool; simulation_release_piece In RAPID, consider the use of ConfJ on, or ConfJ off, or ConfL on, or ConfL off in the case the controller avoids the change of configurations between target points
0001 % Matlab script for RAPID equivalent commands 0002 % please note that variables should be 0003 % declared as global as in RAPID syntaxis 0004 % this script demonstrates the use of functions in the matlab script. This 0005 % script can be translated to RAPID by means of the matlab2RAPID script. 0006 % 0007 % IN ORDER TO SIMULATE THE PROGRAM: 0008 % A) FIRST, LOAD A ROBOT 0009 % robot = load_robot('abb','irb140'); 0010 % OR 0011 % robot = load_robot('abb','irb52'); 0012 % B) NEXT, LOAD SOME EQUIPMENT. 0013 % robot.equipment = load_robot('equipment','tables/table_two_areas'); 0014 % 0015 % C) NOW, LOAD AN END TOOL 0016 % robot.tool= load_robot('equipment','end_tools/parallel_gripper_0'); 0017 % D) FINALLY, LOAD A PIECE TO GRAB BY THE ROBOT 0018 % robot.piece=load_robot('equipment','cylinders/cylinder_tiny'); 0019 % 0020 % E) IF NECESSARY, CHANGE THE POSITION AND ORIENTATION OF THE piece, 0021 % relative to the robot's base reference system. 0022 % 0023 % robot.piece.T0= [1 0 0 -0.1; 0024 % 0 1 0 -0.5; 0025 % 0 0 1 0.2; 0026 % 0 0 0 1]; 0027 % 0028 % during the simulation, call simulation_open_tool; to open the tool and 0029 % simulation_close_tool; to close it. 0030 % 0031 % To grip the piece, call simulation_grip_piece; and 0032 % simulation_release_piece to release it. 0033 % 0034 % The call to each function must be in a correct, otherwise, the result may be 0035 % undesired, thus, typically the correct sequence is: 0036 % simulation_open_tool; 0037 % (approach the piece to grab with MoveL or MoveJ) 0038 % simulation_close_tool; 0039 % simulation_grip_piece; --> the piece will be drawn with the robot 0040 % 0041 % move to a different place with MoveJ or MoveL 0042 % simulation_open_tool; 0043 % simulation_release_piece 0044 % 0045 % In RAPID, consider the use of ConfJ on, or ConfJ off, or ConfL on, or ConfL off 0046 % in the case the controller avoids the change of configurations between target points 0047 function tres 0048 0049 global RT_pos_ini RJ_ini RT_aprox_rec RT_pos_rec 0050 global RT_aprox_dej RT_pos_dej TD_gripper VAR_pieza 0051 global robot 0052 0053 0054 TD_gripper=[1,[[0,0,0.125],[1,0,0,0]],[0.1,[0,0,0.100],[1,0,0,0],0,0,0]]; 0055 0056 RJ_ini=[0,0,0,0,0,0]; 0057 RT_pos_ini=[[0.044,-0.501,0.432],[0.262525,0.622008,0.673812,-0.300276],[0,0,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]]; 0058 0059 RT_aprox_rec=[[0.03,-0.6,0.45],[0.08,0.60337,0.79283,-0.03126],[0,0,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]]; 0060 RT_pos_rec=[[0.0345,-0.629,0.337],[0.261833,0.652321,0.67413,-0.226869],[-1,0,-1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]]; 0061 0062 RT_aprox_dej=[[0.470,-0.460,0.500],[0.07981,0.603204,0.792983,-0.030902],[0,0,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]]; 0063 RT_pos_dej=[[0.470,-0.460,0.450],[0.07981,0.603204,0.792983,-0.030902],[0,0,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]]; 0064 0065 0066 %local function to init simulation variables 0067 init_simulation; 0068 0069 0070 VAR_pieza=0; 0071 %!Reset --> abrir pinza 0072 %!Set --> Cerrar pinza 0073 0074 main 0075 end 0076 0077 0078 function main() 0079 0080 global RJ_ini TD_gripper VAR_pieza 0081 0082 %inicializar pieza 0083 VAR_pieza=0; 0084 0085 MoveAbsJ(RJ_ini,'vmax','z100',TD_gripper, 'wobj0'); 0086 0087 %MoveJ(RT_pos_ini,'vmax','z100',TD_gripper, 'wobj0'); 0088 0089 for i=1:4, 0090 ASIR_DEJAR(); 0091 VAR_pieza=VAR_pieza +1; 0092 %local function to init simulation variables 0093 init_simulation; 0094 end 0095 0096 end 0097 0098 0099 function ASIR_DEJAR() 0100 0101 global RT_aprox_rec RT_aprox_dej TD_gripper 0102 0103 %!Moverse a posición de aproximacion de recogida 0104 MoveJ(RT_aprox_rec,'vmax','z100',TD_gripper, 'wobj0'); 0105 COGER_PIEZA; 0106 %!Moverse a posición base de dejada 0107 MoveJ(RT_aprox_dej,'vmax','z100',TD_gripper, 'wobj0'); 0108 METER_EN_CAJA; 0109 0110 end 0111 0112 0113 function COGER_PIEZA() 0114 global RT_aprox_rec RT_pos_rec TD_gripper 0115 0116 %!Ahora abrir pinza 0117 simulation_open_tool; %Reset do1; 0118 Waittime(0.1);!esperar apertura 0119 %!Coger 0120 MoveL(RT_pos_rec,'vmax','fine',TD_gripper, 'wobj0'); 0121 0122 %!Ahora cerrar pinza 0123 simulation_close_tool; %Set do1; 0124 simulation_grip_piece; 0125 0126 Waittime(0.1); !esperar cierre 0127 %!Subir por seguridad antes de ir al siguiente punto 0128 MoveL(RT_aprox_rec,'vmax','z50',TD_gripper, 'wobj0'); 0129 0130 end 0131 0132 function METER_EN_CAJA() 0133 global RT_pos_dej TD_gripper VAR_pieza 0134 0135 if VAR_pieza==0 0136 %Bajar para meter primera pieza 0137 MoveL(Offs(RT_pos_dej,0,0,-0.105),'v1000','fine',TD_gripper, 'wobj0'); 0138 elseif VAR_pieza==1 0139 MoveL(RT_pos_dej,'v1000','z100',TD_gripper, 'wobj0'); 0140 MoveL(Offs(RT_pos_dej,0,0,-0.055),'v1000','fine',TD_gripper, 'wobj0'); 0141 elseif VAR_pieza==2 0142 MoveL(Offs(RT_pos_dej,0,0,0.05),'v1000','fine',TD_gripper, 'wobj0'); 0143 MoveL(Offs(RT_pos_dej,0,0,-0.005),'v1000','fine',TD_gripper, 'wobj0'); 0144 else 0145 MoveL(Offs(RT_pos_dej,0,0,0.1),'v1000','fine',TD_gripper, 'wobj0'); 0146 MoveL(Offs(RT_pos_dej,0,0,0.045),'v1000','fine',TD_gripper, 'wobj0'); 0147 end 0148 0149 %Ahora abrir pinza 0150 %yes, release the piece 0151 simulation_open_tool; %Reset do1; 0152 simulation_release_piece; 0153 0154 plot_points; 0155 0156 Waittime(0.5); 0157 %Subir por seguridad antes de ir al siguiente punto 0158 MoveL(Offs(RT_pos_dej,0,0,0.105),'v1000','z10',TD_gripper, 'wobj0'); 0159 0160 end 0161 0162 0163 function init_simulation 0164 global robot 0165 robot.piece.T0=eye(4); 0166 robot.tool.Trel=eye(4); 0167 % Now open the tool 0168 simulation_open_tool; %Reset do1; 0169 simulation_release_piece; 0170 %init the position of the piece at the beginning of the simulation 0171 robot.piece.T0(1:3,4)=[0.03 -0.68 0.26]'; 0172 th=-30*pi/180; 0173 u=[1 0 0; 0174 0 cos(th) -sin(th); 0175 0 sin(th) cos(th)]; 0176 robot.piece.T0(1:3,1:3)=u;%eye(3); 0177 %robot.tool.piece_gripped=0; 0178 drawrobot3d(robot, robot.q); 0179 0180 0181 end 0182 0183 function plot_points 0184 x0=0.47; 0185 y0=-0.46; 0186 z0=0.45-0.155; 0187 delta=0.055; 0188 X=[x0 x0-delta x0 x0-delta]; 0189 Y=[y0 y0 y0-delta y0-delta]; 0190 Z=[z0 z0 z0 z0]; 0191 0192 plot3(X', Y', Z', 'LineWidth', 5) 0193 end