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

practice_1_programming

PURPOSE ^

Matlab script for RAPID equivalent commands

SYNOPSIS ^

function practice_1_programming

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

 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 % 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 
0048 function practice_1_programming
0049 global robot TD_gripper RT_initial RT_approach1 RT_grip RT_approach2 RT_release
0050 
0051 %init the position of the piece at the beginning of the simulation
0052 robot.piece.T0(1:3,4)=[-0.1 -0.5 0.2]';
0053 %robot.tool.piece_gripped=0;
0054 drawrobot3d(robot, robot.q);
0055 
0056 
0057 %define the tool
0058 %In RAPID this is done by means of the tooldata structure
0059 TD_gripper=[1,[[0,0,0.125],[1,0,0,0]],[0.1,[0,0,0.100],[1,0,0,0],0,0,0]];
0060 
0061 %define target points FOR SIMULATION
0062 RT_initial=[[0.5,-0.4,0.5],[0.427269,0.289111,0.844060,-0.146350],[-1.000000,0.000000,-1.000000,0.000000],[9E9,9E9,9E9,9E9,9E9,9E9]];
0063 RT_approach1=[[-0.1, -0.5, 0.4],[0.0, 0.70711, 0.70711, 0.0], [-1.00000, -1.00000, 0.00000, 0.00000], [9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0064 RT_grip=[[-0.1, -0.5, 0.28],[0.00000, 0.70711, 0.70711, -0.00000], [-1.00000, -1.00000, 0.00000, 0.00000], [9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0065 RT_approach2=[[0.5, -0.5, 0.4],[0.00000, 0.70711, 0.70711, -0.00000], [-1.00000, -1.00000, 0.00000, 0.00000], [9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0066 RT_release=[[0.5, -0.5, 0.28],[0.00000, 0.70711, 0.70711, -0.00000], [-1.00000, -1.00000, 0.00000, 0.00000], [9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0067 
0068 %replace the above points TO PROGRAM THE REAL ROBOT.
0069 %CONST robtarget RT_initial:=[[500,-400,500],[0.427269,0.289111,0.84406,-0.14635],[-1,0,-1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0070 %CONST robtarget RT_approach1:=[[-100,-500,400],[0,0.70711,0.70711,0],[-1,-1,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0071 %CONST robtarget RT_grip:=[[-97.01,-493.4,246.8],[1.5E-05,-0.707114,-0.7071,-2E-06],[-2,-1,-1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0072 %CONST robtarget RT_approach2:=[[532.11,-422.58,368.01],[6.1E-05,-0.707117,-0.707097,1.5E-05],[-1,-1,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0073 %CONST robtarget RT_release:=[[503.36,-442.47,356.87],[0.000279,0.707036,0.707178,0.000235],[-1,0,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0074 
0075 
0076 main
0077 end
0078 
0079 function main()
0080 
0081 global TD_gripper RT_initial RT_approach1 RT_grip RT_approach2 RT_release
0082 %close the tool
0083 simulation_close_tool; %Set do1;
0084 
0085 %move to the initial point
0086 MoveJ(RT_initial, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0087 
0088 % Now open the tool
0089 simulation_open_tool; %Reset do1;
0090 
0091 %Move to the approaching point
0092 MoveJ(RT_approach1, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0093 %Now, go down to the grabbing target point and
0094 MoveL(RT_grip, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0095 
0096 %and close the tool and grip the piece. These two functions
0097 % must be called to simulate that the gripper has the piece grabbed and the
0098 %tool is closed
0099 simulation_close_tool; %Set do1;
0100 simulation_grip_piece;
0101 
0102 %Now go to the same approach point so that collisions with the table are
0103 %avoided
0104 MoveL(RT_approach1, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0105 
0106 %Move to the approach next to the packaging area
0107 MoveJ(RT_approach2, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0108 %go down to the release point inside the box
0109 MoveL(RT_release, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0110 
0111 %yes, release the piece
0112 simulation_open_tool; %Reset do1;
0113 simulation_release_piece; %Reset do1;
0114 
0115 %now, go up
0116 MoveL(RT_approach2, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0117 
0118 %Now, go back to the initial point
0119 MoveJ(RT_initial, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0120 
0121 end

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