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

test_2

PURPOSE ^

IN ORDER TO SIMULATE THE PROGRAM:

SYNOPSIS ^

function test_2

DESCRIPTION ^

 IN ORDER TO SIMULATE THE PROGRAM:
   A) FIRST, LOAD A ROBOT
       robot = load_robot('abb','irb140');
   B) NEXT, LOAD SOME EQUIPMENT.
       robot.equipment = load_robot('equipment','tables/table_small');
       OR
       robot.equipment = load_robot('equipment','bumper_cutting');
   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 ROBOT'S
   BASE
       robot.piece.T0= [1 0 0 -0.35;
                        0 1 0 -0.55;
                        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 correct, thus, typically the correct
 sequence is:

CROSS-REFERENCE INFORMATION ^

This function calls: This function is called by:

SUBFUNCTIONS ^

SOURCE CODE ^

0001 % IN ORDER TO SIMULATE THE PROGRAM:
0002 %   A) FIRST, LOAD A ROBOT
0003 %       robot = load_robot('abb','irb140');
0004 %   B) NEXT, LOAD SOME EQUIPMENT.
0005 %       robot.equipment = load_robot('equipment','tables/table_small');
0006 %       OR
0007 %       robot.equipment = load_robot('equipment','bumper_cutting');
0008 %   C) NOW, LOAD AN END TOOL
0009 %       robot.tool= load_robot('equipment','end_tools/parallel_gripper_0');
0010 %   D) FINALLY, LOAD A PIECE TO GRAB BY THE ROBOT
0011 %       robot.piece=load_robot('equipment','cylinders/cylinder_tiny');
0012 %
0013 %   E) IF NECESSARY, CHANGE THE POSITION AND ORIENTATION OF THE ROBOT'S
0014 %   BASE
0015 %       robot.piece.T0= [1 0 0 -0.35;
0016 %                        0 1 0 -0.55;
0017 %                        0 0 1 0.2;
0018 %                        0 0 0 1];
0019 %
0020 % during the simulation, call simulation_open_tool; to open the tool and
0021 % simulation_close_tool; to close it.
0022 % To grip the piece, call simulation_grip_piece; and
0023 % simulation_release_piece to release it.
0024 % The call to each function must be correct, thus, typically the correct
0025 % sequence is:
0026 
0027 % simulation_open_tool;
0028 % approach the piece to grab.
0029 % simulation_close_tool;
0030 % simulation_grip_piece; --> the piece will be drawn with the robot
0031 % move to a different place
0032 % simulation_open_tool;
0033 % simulation_release_piece
0034 
0035 function test_2
0036 global TD_tool0 RT_tp1 RT_tp2 RT_tp3 JV_q0
0037 
0038 TD_tool0=[1,[[0,0,0],[1,0,0,0]],[0,[0,0,0],[1,0,0,0],0,0,0]];
0039 
0040 %initial position
0041 JV_q0=[0 0 0 0 0 0]';
0042 %target points
0043 RT_tp1=[[0.3,0.0089,1.0195],[0.2175,0.0971,-0.0689,0.9688],[1,0,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
0044 RT_tp2=[[0.7150,-0.2000,0.5120],[0.7071,0.0,0.7071,0.0000],[-1,-1,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
0045 RT_tp3=[[0.8,0.000,0.3],[0.7071,0.0,0.7071,0.0000],[-1,-1,0,0],[9E9,9E9,9E9,9E9,9E9,9E9]];
0046 
0047 main
0048 end
0049 
0050 function main()
0051 
0052 global TD_tool0 RT_tp1 RT_tp2 RT_tp3 JV_q0
0053 
0054 %The MoveAbsJ function performs a joint coordinate planning to the
0055 %specified joint values
0056  MoveAbsJ(JV_q0, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0057  MoveJ(RT_tp1, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0058  MoveJ(RT_tp2, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0059  MoveL(RT_tp1, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0060  MoveL(RT_tp2, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0061  %Return to tp1
0062  MoveJ(RT_tp1, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0063  
0064  MoveC(RT_tp2, RT_tp3, 'vmax' , 'fine' , TD_tool0, 'wobj0');
0065  
0066  %use the Offs function to move relative to tp1
0067  % The Offs function makes a relative displacement in X, Y and Z directions
0068  %Please note that, by using Offs, the specified axes configuration may
0069  %differ from the one specified in tp1.
0070  MoveJ(Offs(RT_tp1,0.1,0,-0.1), 'vmax' , 'fine' , TD_tool0, 'wobj0');
0071  
0072  %use MoveL inside a Loop, moving incrementally
0073  for i=1:4
0074      MoveL(Offs(RT_tp1,0.1,i*0.1,-0.2), 'vmax' , 'fine' , TD_tool0, 'wobj0');
0075  end
0076  
0077 end

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