Home > arte3.2.0 > RAPID > programs > practice_1_packaging.m

practice_1_packaging

PURPOSE ^

Matlab script for RAPID equivalent commands

SYNOPSIS ^

function practice_1_packaging

DESCRIPTION ^

 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]; 

   The A, B, C, D and E steps can be performed usint the 'teach' application
   by clicking on the Load equipment, load end tool, and load piece
   buttons.

 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

CROSS-REFERENCE INFORMATION ^

This function calls: This function is called by:

SUBFUNCTIONS ^

SOURCE CODE ^

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 %   The A, B, C, D and E steps can be performed usint the 'teach' application
0029 %   by clicking on the Load equipment, load end tool, and load piece
0030 %   buttons.
0031 %
0032 % during the simulation, call simulation_open_tool; to open the tool and
0033 % simulation_close_tool; to close it.
0034 %
0035 % To grip the piece, call simulation_grip_piece; and
0036 % simulation_release_piece to release it.
0037 %
0038 % The call to each function must be in a correct, otherwise, the result may be
0039 % undesired, thus, typically the correct sequence is:
0040 % simulation_open_tool;
0041 % (approach the piece to grab with MoveL or MoveJ)
0042 % simulation_close_tool;
0043 % simulation_grip_piece; --> the piece will be drawn with the robot
0044 %
0045 % move to a different place with MoveJ or MoveL
0046 % simulation_open_tool;
0047 % simulation_release_piece
0048 %
0049 % In RAPID, consider the use of ConfJ on, or ConfJ off, or ConfL on, or ConfL off
0050 % in the case the controller avoids the change of configurations between target points
0051 function practice_1_packaging
0052 
0053 global RT_pos_ini RJ_ini RT_aprox_rec RT_pos_rec
0054 global RT_aprox_dej RT_pos_dej TD_gripper VAR_pieza
0055 global robot
0056 
0057 
0058 TD_gripper=[1,[[0,0,0.125],[1,0,0,0]],[0.1,[0,0,0.100],[1,0,0,0],0,0,0]];
0059 
0060 RJ_ini=[0,0,0,0,0,0];
0061 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]];
0062 
0063 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]];
0064 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]];
0065 
0066 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]];
0067 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]];
0068 
0069 
0070 %local function to init simulation variables
0071 init_simulation;
0072 
0073 
0074 VAR_pieza=0;
0075 %!Reset --> abrir pinza
0076 %!Set --> Cerrar pinza
0077 
0078 main
0079 end
0080 
0081 
0082 function main()
0083 
0084 global RJ_ini TD_gripper VAR_pieza
0085 
0086 %inicializar pieza
0087 VAR_pieza=0;
0088 
0089 MoveAbsJ(RJ_ini,'vmax','z100',TD_gripper, 'wobj0');
0090 
0091 %MoveJ(RT_pos_ini,'vmax','z100',TD_gripper, 'wobj0');
0092 
0093 for i=1:4,
0094     ASIR_DEJAR();
0095     VAR_pieza=VAR_pieza +1;
0096     %local function to init simulation variables
0097     init_simulation;
0098 end
0099 
0100 end
0101 
0102 
0103 function ASIR_DEJAR()
0104 
0105 global  RT_aprox_rec RT_aprox_dej TD_gripper 
0106 
0107 %!Moverse a posici�n de aproximacion de recogida
0108 MoveJ(RT_aprox_rec,'vmax','z100',TD_gripper, 'wobj0');
0109 COGER_PIEZA;
0110 %!Moverse a posici�n base de dejada
0111 MoveJ(RT_aprox_dej,'vmax','z100',TD_gripper, 'wobj0');
0112 METER_EN_CAJA;
0113 
0114 end
0115 
0116 
0117 function COGER_PIEZA()
0118 global RT_aprox_rec RT_pos_rec TD_gripper
0119 
0120 %!Ahora abrir pinza
0121 simulation_open_tool; %Reset do1;
0122 WaitTime(0.1);!esperar apertura
0123 %!Coger
0124 MoveL(RT_pos_rec,'vmax','fine',TD_gripper, 'wobj0');
0125 
0126 %!Ahora cerrar pinza
0127 simulation_close_tool; %Set do1;
0128 simulation_grip_piece;
0129 
0130 Waittime(0.1); !esperar cierre
0131 %!Subir por seguridad antes de ir al siguiente punto
0132 MoveL(RT_aprox_rec,'vmax','z50',TD_gripper, 'wobj0');
0133 
0134 end
0135 
0136 function  METER_EN_CAJA()
0137 global RT_pos_dej TD_gripper VAR_pieza
0138 
0139 if VAR_pieza==0
0140     %Bajar para meter primera pieza
0141     MoveL(Offs(RT_pos_dej,0,0,-0.105),'v1000','fine',TD_gripper, 'wobj0');
0142 elseif VAR_pieza==1
0143     MoveL(Offs(RT_pos_dej,-0.055,0,0),'v1000','z100',TD_gripper, 'wobj0');
0144     MoveL(Offs(RT_pos_dej,-0.055,0,-0.105),'v1000','fine',TD_gripper, 'wobj0');
0145 elseif VAR_pieza==2
0146     MoveL(Offs(RT_pos_dej,0,-0.055,0),'v1000','fine',TD_gripper, 'wobj0');
0147     MoveL(Offs(RT_pos_dej,0,-0.055,-0.105),'v1000','fine',TD_gripper, 'wobj0');
0148 else
0149     MoveL(Offs(RT_pos_dej,-0.055,-0.055,0),'v1000','fine',TD_gripper, 'wobj0');
0150     MoveL(Offs(RT_pos_dej,-0.055,-0.055,-0.105),'v1000','fine',TD_gripper, 'wobj0');
0151 end
0152 
0153 %Ahora abrir pinza
0154 %yes, release the piece
0155 simulation_open_tool; %Reset do1;
0156 simulation_release_piece; 
0157 
0158 plot_points;
0159 
0160 Waittime(0.5);
0161 %Subir por seguridad antes de ir al siguiente punto
0162 MoveL(Offs(RT_pos_dej,0,0,0.105),'v1000','z10',TD_gripper, 'wobj0');
0163 
0164 end
0165 
0166 
0167 function init_simulation
0168 global robot
0169 robot.piece.T0=eye(4);
0170 robot.tool.Trel=eye(4);
0171 % Now open the tool
0172 simulation_open_tool; %Reset do1;
0173 simulation_release_piece;
0174 %init the position of the piece at the beginning of the simulation
0175 robot.piece.T0(1:3,4)=[0.03 -0.68 0.26]';
0176 th=-30*pi/180;
0177 u=[1 0 0;
0178    0 cos(th) -sin(th);
0179    0 sin(th) cos(th)];
0180 robot.piece.T0(1:3,1:3)=u;%eye(3);
0181 %robot.tool.piece_gripped=0;
0182 drawrobot3d(robot, robot.q);
0183 
0184 
0185 end
0186 
0187 function plot_points
0188 x0=0.47;
0189 y0=-0.46;
0190 z0=0.45-0.155;
0191 delta=0.055;
0192 X=[x0 x0-delta x0 x0-delta];
0193 Y=[y0 y0 y0-delta y0-delta];
0194 Z=[z0 z0 z0 z0];
0195 
0196 plot3(X', Y', Z', 'LineWidth', 5)
0197 end

Generated on Fri 03-Jan-2014 12:20:01 by m2html © 2005