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

basic_robot_program

PURPOSE ^

IN ORDER TO SIMULATE THE PROGRAM:

SYNOPSIS ^

function basic_robot_program

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 basic_robot_program
0036 
0037 global RT_tp1 RT_tp2 RT_tp3 RT_tp4 TD_gripper
0038 
0039 TD_gripper=[1,[[0,0,0.125],[1,0,0,0]],[0.1,[0,0,0.100],[1,0,0,0],0,0,0]];
0040 RT_tp1=[[0.541,0.1171,0.713],[0.727812,-0.115363,0.676004,-0.000468],[0,0,-1,1],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0041 RT_tp2=[[0.515,-0.200,0.712],[0.7071,0,0.7071,0],[-1,-2,1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0042 RT_tp3=[[0.515,0,0.912],[0.7071,0,0.7071,0],[0,-1,0,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0043 RT_tp4=[[0.515,0,0.512],[0.7071,0,0.7071,0],[0,0,-1,0],[9E+09,9E+09,9E+09,9E+09,9E+09,9E+09]];
0044 
0045 main
0046 end
0047 
0048 function main
0049 
0050 global RT_tp1 RT_tp2 RT_tp3 RT_tp4 TD_gripper
0051 
0052 MoveJ(RT_tp1, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0053 MoveJ(RT_tp2, 'vmax' , 'fine' , TD_gripper, 'wobj0');
0054 MoveJ(RT_tp3,'vmax','fine', TD_gripper, 'wobj0');
0055 MoveL(RT_tp4,'vmax','fine', TD_gripper, 'wobj0');
0056 end

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