MoveP (Process Move – Circular Move)

Also checkout the new CB3 forum

MoveP – Process Move Moving the Robot in Circular Move

The MoveP function is introduced for Process tasks.

The syntax for MoveP is two waypoints i.e. the next position and a via point and the radius as a parameter.

universal_robots_zacobria_moveP_1

The program below draws a circle.

universal_robots_zacobria_moveP_2

Program “Circle_min.txt”

Program
Robot Program
MoveP
Waypoint_1
CircleMove
Waypoint_2
Waypoint_3
Waypoint_3
MoveP
Waypoint_3
CircleMove
Waypoint_4
Waypoint_5

 

Program “Circle_min.script”

def circle_min():

set_analog_inputrange(0, 0)

set_analog_inputrange(1, 0)

set_analog_inputrange(2, 0)

set_analog_inputrange(3, 0)

set_analog_outputdomain(0, 0)

set_analog_outputdomain(1, 0)

set_tool_voltage(24)

set_runstate_outputs([])

set_payload(0.0)

set_gravity([0.0, 0.0, 9.82])

while (True):

$ 1 “Robot Program”

$ 2 “MoveP”

$ 3 “Waypoint_1″

movep(p[-0.5855971806671894, 0.20763167238928246, 0.07550319928745566, 0.6405873044452095, -3.071940616768458, 0.026070362768991707], a=1.2, v=0.25, r=0.025)

$ 4 “CircleMove”

$ 5 “Waypoint_2″

$ 6 “Waypoint_3″

movec(p[-0.6552053520364435, 0.20814432868498473, 0.05497712244299978, 0.6420954022873315, -3.0707961749619, 0.02459624334927117], p[-0.6566043998391788, 0.2770636231977118, 0.05506985067080796, 0.6423195981777231, -3.0742335265890093, 0.029393002058536455], a=1.2, v=0.25, r=0.025)

$ 7 “Waypoint_3″

movep(p[-0.6566043998391788, 0.2770636231977118, 0.05506985067080796, 0.6423195981777231, -3.0742335265890093, 0.029393002058536455], a=1.2, v=0.25, r=0.025)

$ 8 “MoveP”

$ 9 “Waypoint_3″

movep(p[-0.6566043998391788, 0.2770636231977118, 0.05506985067080796, 0.6423195981777231, -3.0742335265890093, 0.029393002058536455], a=1.2, v=0.25, r=0.025)

$ 10 “CircleMove”

$ 11 “Waypoint_4″

$ 12 “Waypoint_5″

movec(p[-0.5865144622138906, 0.2775296529322894, 0.05631928049682099, -0.6402521828636203, 3.073245510255796, -0.03566808080779445], p[-0.5854931145717062, 0.20761008476478102, 0.05712855652755951, 0.6409596020239017, -3.071863854166044, 0.02588460628260649], a=1.2, v=0.25, r=0.025)

end

end

 

 

Circle and Square test pattern.

Program “circle_sq_pat_fast.txt”

Result of drawing a circle test.

universal_robots_zacobria_moveP_4

Code for “circle_sq_pat_fast.txt”

def circle_sq_pat_fast():
set_analog_inputrange(0, 0)
set_analog_inputrange(1, 0)
set_analog_inputrange(2, 0)
set_analog_inputrange(3, 0)
set_analog_outputdomain(0, 0)
set_analog_outputdomain(1, 0)
set_tool_voltage(24)
set_runstate_outputs([])
set_payload(0.0)
set_gravity([0.0, 0.0, 9.82])
while (True):
$ 1 “Robot Program”
$ 2 “MoveJ”
$ 3 “Waypoint_9″
movej([0.6236825723301582, -1.477339167481995, 2.478097719134525, -2.5575642827418985, -1.5571205043625342, 2.781621040141847], a=1.3962634015954636, v=1.0471975511965976)
$ 4 “Waypoint_10″
movej([0.6236448619691226, -1.4474532845166352, 2.4859203692109046, -2.5962346800626244, -1.5571205043625342, 2.7815076214373375], a=1.3962634015954636, v=1.0471975511965976)
$ 5 “Waypoint_11″
movej([0.6236825723301582, -1.477339167481995, 2.4780882915442657, -2.5575642827418985, -1.5571205043625342, 2.781621040141847], a=1.3962634015954636, v=1.0471975511965976)
$ 6 “Waypoint_12″
movej([0.714226440276918, -1.5329328874650308, 2.5526487507978564, -2.5756847064367876, -1.5568450589372969, 2.874492455491799], a=1.3962634015954636, v=1.0471975511965976)
$ 7 “Waypoint_13″
movej([0.7142170126866592, -1.5033662386848032, 2.560409472791512, -2.6125336094298417, -1.5568450589372969, 2.874492455491799], a=1.3962634015954636, v=1.0471975511965976)
$ 8 “Waypoint_14″
movej([0.714226440276918, -1.5329328874650308, 2.5526487507978564, -2.5756847064367876, -1.5568450589372969, 2.874492455491799], a=1.3962634015954636, v=1.0471975511965976)
$ 9 “Waypoint_15″
movej([0.8252617221320047, -1.5918062775490593, 2.6108257966930766, -2.572964383256948, -1.5561244714621552, 2.985678738585739], a=1.3962634015954636, v=1.0471975511965976)
$ 10 “Waypoint_16″
movej([0.8252428669514869, -1.5604846269140245, 2.6186767359318197, -2.6124039880532592, -1.5561244714621552, 2.985678738585739], a=1.3962634015954636, v=1.0471975511965976)
$ 11 “Waypoint_17″
movej([0.8252617221320047, -1.591815705139318, 2.610816369102818, -2.572964383256948, -1.5561244714621552, 2.985678738585739], a=1.3962634015954636, v=1.0471975511965976)
$ 12 “Waypoint_18″
movej([0.7331083376267294, -1.3915349678072964, 2.3710384451741837, -2.5329090769218716, -1.5570318330824549, 2.89377095079202], a=1.3962634015954636, v=1.0471975511965976)
$ 13 “Waypoint_19″
movej([0.7331083376267294, -1.3690286317845626, 2.3773876236131737, -2.5608917627081453, -1.5570318330824549, 2.89377095079202], a=1.3962634015954636, v=1.0471975511965976)
$ 14 “Waypoint_20″
movej([0.7331083376267294, -1.3915443953975553, 2.3710384451741837, -2.5329090769218716, -1.5570318330824549, 2.8937547481199473], a=1.3962634015954636, v=1.0471975511965976)
$ 15 “Waypoint_21″
movej([0.8240010264130678, -1.441522985098124, 2.438002522909194, -2.5499123910921577, -1.5559948500855727, 2.9840840816670857], a=1.3962634015954636, v=1.0471975511965976)
$ 16 “Waypoint_22″
movej([0.8240198815935855, -1.4198678933641073, 2.443904539556929, -2.577150628811502, -1.5559948500855727, 2.9840840816670857], a=1.3962634015954636, v=1.0471975511965976)
$ 17 “Waypoint_23″
movej([0.8240010264130678, -1.441513557507865, 2.438002522909194, -2.5499123910921577, -1.5559948500855727, 2.9840840816670857], a=1.3962634015954636, v=1.0471975511965976)
$ 18 “Waypoint_24″
movej([0.9316529346760483, -1.4809353233841405, 2.491492413807992, -2.562170910937701, -1.554650891167726, 3.0918942647943353], a=1.3962634015954636, v=1.0471975511965976)
$ 19 “Waypoint_25″
movej([0.9316435070857895, -1.4579481738666173, 2.497083319977184, -2.590648221638516, -1.554650891167726, 3.0918942647943353], a=1.3962634015954636, v=1.0471975511965976)
$ 20 “Waypoint_26″
movej([0.9316529346760483, -1.4809353233841405, 2.4914829862177332, -2.562187113609774, -1.554650891167726, 3.0918942647943353], a=1.3962634015954636, v=1.0471975511965976)
$ 21 “Waypoint_27″
movej([0.8233087408834951, -1.311938526326118, 2.255112659994481, -2.492562122489485, -1.556570488360478, 2.9845130090606924], a=1.3962634015954636, v=1.0471975511965976)
$ 22 “Waypoint_28″
movej([0.8233087408834951, -1.291530644063278, 2.26065236316329, -2.5190874306534026, -1.556570488360478, 2.9845130090606924], a=1.3962634015954636, v=1.0471975511965976)
$ 23 “Waypoint_29″
movej([0.8233087408834951, -1.311938526326118, 2.2551032324042213, -2.4925459198174122, -1.556570488360478, 2.9845130090606924], a=1.3962634015954636, v=1.0471975511965976)
$ 24 “Waypoint_30″
movej([0.9122053691275309, -1.3541752492135488, 2.3195823187871376, -2.519265660046203, -1.5554524920032318, 3.074064614348338], a=1.3962634015954636, v=1.0471975511965976)
$ 25 “Waypoint_31″
movej([0.9122242243080487, -1.3334427702244058, 2.3253765732845233, -2.5457509049462597, -1.5554524920032318, 3.074064614348338], a=1.3962634015954636, v=1.0471975511965976)
$ 26 “Waypoint_32″
movej([0.9122053691275309, -1.3541752492135488, 2.31956346360662, -2.51924945737413, -1.5554524920032318, 3.074064614348338], a=1.3962634015954636, v=1.0471975511965976)
$ 27 “Waypoint_33″
movej([1.0127134202043575, -1.38483290347964, 2.365885279597575, -2.5321885014309546, -1.5538006823160018, 3.17258729881069], a=1.3962634015954636, v=1.0471975511965976)
$ 28 “Waypoint_34″
movej([1.0127417029751342, -1.3578360879722504, 2.373255398949942, -2.565830989097761, -1.5538006823160018, 3.17258729881069], a=1.3962634015954636, v=1.0471975511965976)
$ 29 “Waypoint_35″
movej([1.0127228477946164, -1.38483290347964, 2.365885279597575, -2.5321885014309546, -1.5538006823160018, 3.17258729881069], a=1.3962634015954636, v=1.0471975511965976)
$ 30 “Waypoint_36″
movej([0.7152056121717583, -1.534057538262842, 2.547377085205383, -2.559847121791548, -1.558505413376884, 2.877342400048221], a=1.3962634015954636, v=1.0471975511965976)
$ 31 “Waypoint_5″
movej([0.7152150397620171, -1.509649423991981, 2.5542070771391625, -2.590340370869133, -1.558505413376884, 2.877342400048221], a=1.3962634015954636, v=1.0471975511965976)
$ 32 “MoveP”
$ 33 “Waypoint_1″
movep(p[-0.16491422010377074, -0.2889616960490904, 0.08977820818409682, -2.990867253088674, 0.9112659997294901, -0.03714440710006258], a=1.2, v=0.25, r=0.025)
$ 34 “MoveP”
$ 35 “Waypoint_1″
movep(p[-0.16491422010377074, -0.2889616960490904, 0.08977820818409682, -2.990867253088674, 0.9112659997294901, -0.03714440710006258], a=1.2, v=0.25, r=0.025)
$ 36 “CircleMove”
$ 37 “Waypoint_3″

$ 38 “Waypoint_4″
movec(p[-0.11334423078220371, -0.33756318667154395, 0.0893106872941587, -2.9906295321371448, 0.9084318970986581, -0.03600700860586537], p[-0.16180156505488658, -0.38923336070997144, 0.09094760731659506, -2.9907473981412718, 0.9078415477539128, -0.03613806271628099], a=1.2, v=0.1, r=0.025)
$ 39 “CircleMove”
$ 40 “Waypoint_7″

$ 41 “Waypoint_8″
movec(p[-0.21343313150120966, -0.3409373476491314, 0.09104685832970001, -2.9908313209631068, 0.9091432987361415, -0.036845622903562865], p[-0.16566185083507928, -0.2896398133352871, 0.08977500519394872, -2.9869359356408522, 0.9066946880373195, -0.04171997485037223], a=1.2, v=0.1, r=0.0)
$ 42 “MoveJ”
$ 43 “Waypoint_2″
movej([0.7153133743221072, -1.5511373021998727, 2.53837858133081, -2.52716824969675, -1.5586913006893992, 2.875358878999821], a=1.3962634015954636, v=1.0471975511965976)
$ 44 “MoveL”
$ 45 “Waypoint_2″
movel([0.7153133743221072, -1.5511373021998727, 2.53837858133081, -2.52716824969675, -1.5586913006893992, 2.875358878999821], t=3.0)
$ 46 “Waypoint_9″
movel([0.6236825723301582, -1.477339167481995, 2.478097719134525, -2.5575642827418985, -1.5571205043625342, 2.781621040141847], a=1.2, v=0.25)
$ 47 “Waypoint_10″
movel([0.6236448619691226, -1.4474532845166352, 2.4859203692109046, -2.5962346800626244, -1.5571205043625342, 2.7815076214373375], a=1.2, v=0.25)
$ 48 “Waypoint_16″
movel([0.8252428669514869, -1.5604846269140245, 2.6186767359318197, -2.6124039880532592, -1.5561244714621552, 2.985678738585739], a=1.2, v=0.25)
$ 49 “Waypoint_34″
movel([1.0127417029751342, -1.3578360879722504, 2.373255398949942, -2.565830989097761, -1.5538006823160018, 3.17258729881069], a=1.2, v=0.25)
$ 50 “Waypoint_28″
movel([0.8233087408834951, -1.291530644063278, 2.26065236316329, -2.5190874306534026, -1.556570488360478, 2.9845130090606924], a=1.2, v=0.25)
$ 51 “Waypoint_10″
movel([0.6236448619691226, -1.4474532845166352, 2.4859203692109046, -2.5962346800626244, -1.5571205043625342, 2.7815076214373375], a=1.2, v=0.25)
$ 52 “Waypoint_9″
movel([0.6236825723301582, -1.477339167481995, 2.478097719134525, -2.5575642827418985, -1.5571205043625342, 2.781621040141847], a=1.2, v=0.25)
$ 53 “Waypoint_10″
movel([0.6236448619691226, -1.4474532845166352, 2.4859203692109046, -2.5962346800626244, -1.5571205043625342, 2.7815076214373375], a=1.2, v=0.25)
$ 54 “Waypoint_34″
movel([1.0127417029751342, -1.3578360879722504, 2.373255398949942, -2.565830989097761, -1.5538006823160018, 3.17258729881069], a=1.2, v=0.25)
$ 55 “Waypoint_35″
movel([1.0127228477946164, -1.38483290347964, 2.365885279597575, -2.5321885014309546, -1.5538006823160018, 3.17258729881069], a=1.2, v=0.25)
$ 56 “Waypoint_27″
movel([0.8233087408834951, -1.311938526326118, 2.255112659994481, -2.492562122489485, -1.556570488360478, 2.9845130090606924], a=1.2, v=0.25)
$ 57 “Waypoint_28″
movel([0.8233087408834951, -1.291530644063278, 2.26065236316329, -2.5190874306534026, -1.556570488360478, 2.9845130090606924], a=1.2, v=0.25)
$ 58 “Waypoint_16″
movel([0.8252428669514869, -1.5604846269140245, 2.6186767359318197, -2.6124039880532592, -1.5561244714621552, 2.985678738585739], a=1.2, v=0.25)
$ 59 “Waypoint_17″
movel([0.8252617221320047, -1.591815705139318, 2.610816369102818, -2.572964383256948, -1.5561244714621552, 2.985678738585739], a=1.2, v=0.25)
$ 60 “Waypoint_30″
movel([0.9122053691275309, -1.3541752492135488, 2.3195823187871376, -2.519265660046203, -1.5554524920032318, 3.074064614348338], a=1.2, v=0.25)
$ 61 “Waypoint_31″
movel([0.9122242243080487, -1.3334427702244058, 2.3253765732845233, -2.5457509049462597, -1.5554524920032318, 3.074064614348338], a=1.2, v=0.25)
$ 62 “Waypoint_13″
movel([0.7142170126866592, -1.5033662386848032, 2.560409472791512, -2.6125336094298417, -1.5568450589372969, 2.874492455491799], a=1.2, v=0.25)
$ 63 “Waypoint_12″
movel([0.714226440276918, -1.5329328874650308, 2.5526487507978564, -2.5756847064367876, -1.5568450589372969, 2.874492455491799], a=1.2, v=0.25)
$ 64 “Waypoint_18″
movel([0.7331083376267294, -1.3915349678072964, 2.3710384451741837, -2.5329090769218716, -1.5570318330824549, 2.89377095079202], a=1.2, v=0.25)
$ 65 “Waypoint_19″
movel([0.7331083376267294, -1.3690286317845626, 2.3773876236131737, -2.5608917627081453, -1.5570318330824549, 2.89377095079202], a=1.2, v=0.25)
$ 66 “Waypoint_25″
movel([0.9316435070857895, -1.4579481738666173, 2.497083319977184, -2.590648221638516, -1.554650891167726, 3.0918942647943353], a=1.2, v=0.25)
$ 67 “Waypoint_26″
movel([0.9316529346760483, -1.4809353233841405, 2.4914829862177332, -2.562187113609774, -1.554650891167726, 3.0918942647943353], a=1.2, v=0.25)
$ 68 “Waypoint_56″
movel([0.6857898048356728, -1.4664200301787766, 2.46424642229637, -2.5449893673746145, -1.559161190163735, 2.846549844953611], a=1.2, v=0.25)
$ 69 “Waypoint_57″
movel([0.6857615220648962, -1.444068600649273, 2.470539035193807, -2.572899572568657, -1.559161190163735, 2.846549844953611], a=1.2, v=0.25)
$ 70 “Waypoint_58″
movel([0.8261048491057192, -1.5164781056505041, 2.5586113980362324, -2.581101480220454, -1.5564732723280414, 2.984610237077354], a=1.2, v=0.25)
$ 71 “Waypoint_59″
movel([0.9584046264451206, -1.3853783998309852, 2.391893489228279, -2.54941865301026, -1.5525863447747374, 3.1224113744637076], a=1.2, v=0.25)
$ 72 “Waypoint_60″
movel([0.8235067202789316, -1.3332501533701404, 2.3080234092299854, -2.510748243705309, -1.5562626375910948, 2.984885682502591], a=1.2, v=0.25)
$ 73 “Waypoint_61″
movel([0.6852955050931232, -1.446474112621795, 2.463446381008035, -2.5477753760911632, -1.5608778105392558, 2.8467766823626297], a=1.2, v=0.25)
$ 74 “Waypoint_67″
movel([0.685314360273641, -1.4755653168399907, 2.455468818046839, -2.5103994428394225, -1.5608778105392558, 2.8467928850347026], a=1.2, v=0.25)
$ 75 “Waypoint_65″
movel([0.7512009251621345, -1.5109909093657465, 2.505013738595499, -2.5253220079446472, -1.558318639231726, 2.9114709918456603], a=1.2, v=0.25)
$ 76 “Waypoint_6″
movel([0.7512197803426524, -1.483377235442442, 2.5124875678323004, -2.56041422729832, -1.558318639231726, 2.9114709918456603], a=1.2, v=0.25)
$ 77 “MoveP”
$ 78 “Waypoint_62″
movep(p[-0.1654608094368805, -0.3050515583190921, 0.09074255506523285, -2.978974595500004, 0.9047540945859917, -0.047590010174714766], a=1.2, v=0.25, r=0.025)
$ 79 “CircleMove”
$ 80 “Waypoint_63″

$ 81 “Waypoint_64″
movec(p[-0.12918811512289607, -0.3388251479128196, 0.09159825532482757, -2.975159172094294, 0.9091969875160618, -0.047828483334255455], p[-0.16272947830853993, -0.37540537740146757, 0.09174121003793413, -2.9746820405209093, 0.9083317574827601, -0.04840660978457683], a=1.2, v=0.1, r=0.025)
$ 82 “CircleMove”
$ 83 “Waypoint_630″

$ 84 “Waypoint_640″
movec(p[-0.19926293395194192, -0.3409418682706826, 0.09118984712675672, -2.9760891489920756, 0.9128001319285083, -0.04836586638902162], p[-0.16547861949671744, -0.3050714752983104, 0.0907832937936452, -2.9791296124329074, 0.905101737557798, -0.04752396969079929], a=1.2, v=0.1, r=0.0)
$ 85 “MoveJ”
$ 86 “Waypoint_66″
movej([0.7511767010488593, -1.5140361935922029, 2.504185408144801, -2.5211119017983057, -1.5582299559674224, 2.911640676486103], a=1.3962634015954636, v=1.0471975511965976)
$ 87 “Waypoint_9″
movej([0.6236825723301582, -1.477339167481995, 2.478097719134525, -2.5575642827418985, -1.5571205043625342, 2.781621040141847], a=1.3962634015954636, v=1.0471975511965976)
end
end

Disclaimer: While the Zacobria Pte. Ltd. believes that information and guidance provided is correct, parties must rely upon their skill and judgement when making use of them. Zacobria Pte. Ltd. assumes no liability for loss or damage caused by error or omission, whether such an error or omission is the result of negligence or any other cause. Where reference is made to legislation it is not to be considered as legal advice. Any and all such liability is disclaimed.

If you need specific advice (for example, medical, legal, financial or risk management), please seek a professional who is licensed or knowledgeable in that area.

Author:
By Zacobria Lars Skovsgaard
Accredited Universal Robots support Centre and Forum.

Also check out the CB3 forum



42 thoughts on “MoveP (Process Move – Circular Move)

  1. Milad

    Hi,
    I’ve written a script code for a path traversing for UR5, but the most annoying thing is the error of “Circular_ARC_With_Zero_Radius” when I use Movep, when I change it to MoveL there would be no errors, how can I tackle this problem?
    here is part of my script:
    speed=0.030000
    blendRad=0.001000
    acceleration=1.000000
    movep(p[-0.548490, -0.153150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
    movep(p[-0.504490, -0.153150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
    movep(p[-0.548490, -0.195150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
    movep(p[-0.504490, -0.153150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
    movep(p[-0.504490, -0.180150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
    movep(p[-0.504490, -0.199150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)

    I receive error at the end of executing first command.
    Regards
    Milad

    Reply
    1. zacopressadmin Post author

      Hi Milad

      Thanks for the question

      How big id the radius in the circle you try to draw ?

      Author:
      By Zacobria Lars Skovsgaard
      Accredited Universal Robots support Centre and Forum.


      Reply
      1. Milad

        they are simple lines, and since I want to have constant speed during the motion I’m using Movep
        so I don’t know why I get that error, I decrease the speed to a very very low speed, but still the problem persist.
        Thanks for your cooperation

        Reply
        1. zacopressadmin Post author

          Hi Milad

          I tried the program on a UR3 – so I had to change the X value because the UR3 has a max reach of 500mm, but the rest of the data are the same.

          And I run the program and got the same messages.

          I then changed the script to have a wait in between the moves and I also changed the acceleration to 0.3 in order to reduce the inertia.

          And then the program can execute without any messages and the robot moves to the positions.

          When programming with script it is important to control the execution flow – and in this case make time for the robot to actually reach to positions before the next move command is given. Whereas in Polyscope the robot control by itself to reach a position before moving on to the next position.

          I tried this script and it run on the robot. Maybe the wait (sleep) can be different and shorter and fine tuned.

          def move():
          movep(p[-0.348490, -0.153150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
          sleep(0.5)
          movep(p[-0.304490, -0.153150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
          sleep(0.5)
          movep(p[-0.348490, -0.195150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
          sleep(0.5)
          movep(p[-0.304490, -0.153150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
          sleep(0.5)
          movep(p[-0.304490, -0.180150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
          sleep(0.5)
          movep(p[-0.304490, -0.199150, 0.261070, 2.221400, 2.221400, 0.000000], a=acceleration, v=speed, r=blendRad)
          sleep(0.5)
          end

          Author:
          By Zacobria Lars Skovsgaard
          Accredited Universal Robots support Centre and Forum.


          Reply
  2. Rahul

    Hello,

    I have a problem with vibration of the TCP of a UR5 robot.The robot is running the latest software and I want to move the TCP through a sector of a circle(around 40 degree). Initially I used move L and the program had only two waypoints(start and end).The robot was vibrating while i ran the program and then I used the move p with circular move as stated in this website.But still the vibration is there.The strange thing is that the vibration is still there even when there is no work piece in the TCP. So is it some problem with the robot joints or is there any software solution for it?

    Reply
      1. Rahul

        Hi Lars
        Yes.The vibration is visible in most of the programs but it’s very high in the program I mentioned above.
        I tried running that program at different robot speeds and the vibration was almost same on each run.I haven’t noticed this vibration while using the arrows keys for moving.

        I tried the same program in 3 different UR5 robot(running same and latest software update) and 2 of them ran without vibration and one had a little vibration but it was acceptable.

        So what would be the problem? Is there any method to factory reset the robot or recalibrate it? I am also not sure whether it will solve the issue.

        Reply
        1. zacopressadmin Post author

          Hi Rahul

          I have not experienced this before. According to your description when it appear in different programs on one particular robot, but not on other robots – then it might seem like it could be hardware related. So maybe consider to get it checked by your robot provider.

          Author:
          By Zacobria Lars Skovsgaard
          Accredited Universal Robots support Centre and Forum.

          Also check out the CB3 forum

          Reply
  3. Sebastian Isenberg

    Hi,
    I’m trying to use CircleMove with relativ positions, is this possible? I’m trying it for a while now, but the robot doesn’t move the tool on the circle it is expected to do.

    I hope you can help me.

    Best regards
    Sebastian

    Reply
  4. waspinator

    I’m trying to draw a circle in the XY plane, but at the very end of the circle I get an error:

    Security Stopped
    SECURITY CHECK: Torque limit violation

    and

    Security Stopped
    Force limit protective stop

    It ALMOST reaches its final waypoint. ~1mm off. Any idea why it would be doing this?

    Thanks


    Robot Program
    MoveJ
    - Waypoint_1 (0, 400, Z)
    MoveP
    - Waypoint_1
    - CircleMove
    - Waypoint_2 (100, 500, Z)
    - Waypoint_3 (0, 600, Z)
    - Waypoint_3
    MoveP
    - Waypoint_3
    CircleMove
    - Waypoint_4 (-100, 500, Z)
    - Waypoint_1

    Reply
    1. zacopressadmin Post author

      Hi Waspinator

      Thanks for your question.

      It couuld be because of inertia from the move. Maybe you need to look at your acceleration/deceleration setting.

      Or you might consider to insert a StopL(1.0) after the end of the circle. There can be other values for 1.0 argument depending on how hard the inertia is. Or you can consider to continue to another Waypoint that is in the direction of the move if the scenario allow that – then the inertia is carried forward.

      Robot Program
      MoveJ
      - Waypoint_1 (0, 400, Z)
      MoveP
      - Waypoint_1
      - CircleMove
      - Waypoint_2 (100, 500, Z)
      - Waypoint_3 (0, 600, Z)
      - Waypoint_3
      MoveP
      - Waypoint_3
      CircleMove
      - Waypoint_4 (-100, 500, Z)
      - Waypoint_1
      - StopL(1.0)

      Author:
      By Zacobria Lars Skovsgaard
      Authorised Universal-Robots Distributor.

      Reply
  5. Min Xiang

    Hi Lars,

    I have a question about TCP position setup. Is it the only way to specify the TCP position by entering numbers of x,y,z in the TCP setup page? It will be not so accurate because we need to measure it. Is there any convenient way, for example, using 4 or 5 reference points to calculate the TCP like the other brand Robots(KUKA, Motoman) ? I am looking forward to your reply. Thank you !

    Reply
    1. zacopressadmin Post author

      Hi Min Xiang

      Thanks for your question.

      Yes on CB3 you can teach it in the TCP menu. Approach a point from 4 different angles and teach the position from all 4 different aproach anles and the robot will learn the TCP position.

      Author:
      By Zacobria Lars Skovsgaard
      Authorised Universal-Robots Distributor.

      Reply
      1. Min Xiang

        Hi Lars,

        Thank you very much! Probably I am using the old version of UR5 and UR10. That’s why I can not use the method to find TCP. Now my question is , does this method exist in the newest version of UR5 and UR10 except for UR3/CB3?

        Reply
  6. ben

    Thanks Lars for the answer !

    It help me. Is it possible to ask Universal Robots to develop an other type of tool orientation interpolation

    during the movec ?

    Reply
    1. zacopressadmin Post author

      Hi Ben

      Thanks for your email.

      I believe it is linear – I have not informations on the SLERP.

      Regards
      Lars

      Reply
  7. ben

    yes I’m using the UR10 robot. The motion is a circular movement.

    The robot performs the circular motion, but its orientation during the motion is not what expected. I

    mean,the tool orientation interpolation from the start to the end point is not very good. Moreover, the

    tool orientation at the end of the motion is not the right one. I need the robot to perform the circular

    motion properly because if the tool orientation is not what expected there are risks for my tool and I

    loose precision for my experiments

    Reply
    1. zacopressadmin Post author

      I think I need to see a video of what the motion is.

      And a also explanation on the video for what you expect.

      Reply
  8. ben

    I expect the robot to reach the following pose : [0,1000 mm,80 mm,2.2214411881580385, 2.2214417499998165, 0]

    See the code :

    def testmouvementcirculaire2():
    set_analog_inputrange(0, 0)
    set_analog_inputrange(1, 0)
    set_analog_inputrange(2, 0)
    set_analog_inputrange(3, 0)
    set_analog_outputdomain(0, 0)
    set_analog_outputdomain(1, 0)
    set_tool_voltage(0)
    set_runstate_outputs([])
    set_payload(0.0)
    set_gravity([0.0, 0.0, 9.82])
    $ 1 “Programme de robot”
    $ 2 “DéplacementA”
    $ 3 “Point_de_pass_4″
    movej([-0.6284904840803244, -2.463471927136585, -1.0154715197138304, -1.3258316115057807, 1.582330157008739, -0.34707380895619805], a=1.3962634015954636, v=1.0471975511965976)
    $ 4 “DéplacementP”
    $ 5 “Point_de_pass_1″
    movep(p[0.7071068000803378, 4.796873878642146E-10, 0.08000000010201738, 3.1415926535893797, 1.0304558841628937E-6, 1.2394645269881283E-6], a=1.2, v=0.05, r=0.0)
    $ 6 “MouvCercle”
    $ 7 “Point_de_pass_2″

    $ 8 “Point_de_pass_3″
    movec(p[0.7071068000803379, 0.7071067995784731, 0.08000000010201744, -2.9024520981635957, -1.202235652075066, -5.149122323008E-7], p[1.9933919221160015E-10, 0.999999999718092, 0.08000000010201717, 2.2214411881580385, 2.2214417499998165, 1.454230456155269E-6], a=1.2, v=0.05, r=0.0)
    $ 9 “pos≔get_actual_tcp_pose()”
    global pos = get_actual_tcp_pose()
    varmsg(“pos”,pos)
    $ 10 “inv_pos≔get_inverse_kin(pos)”
    global inv_pos = get_inverse_kin(pos)
    varmsg(“inv_pos”,inv_pos)
    $ 11 “joint≔get_actual_joint_positions()”
    global joint = get_actual_joint_positions()
    varmsg(“joint”,joint)
    end

    Reply
    1. zacopressadmin Post author

      Are you using a UR10 ?

      Is this a circular move ?

      Does it have a linear path between start and the via point ?

      What happens when you execute the program ?

      Reply
    1. zacopressadmin Post author

      Hi Ben

      Can you describe what you try expect the movement to be and orientation of the tool head ?

      Can you list the entire code ?

      Regards
      Lars

      Reply
  9. ben

    Hi Mr Zacorbia,

    I made a lot of tests on the moveC function of UR script, but I didn’t manage to resolve the problem

    on the tool orientation. Please have a look on this code :

    This is a rotation of 90° around the Z axis with a radius of 1 meter :

    # “Point_de_pass_1″
    movep(p[0.7071068000803378, 4.796873878642146E-10, 0.08000000010201738, 3.1415926535893797, 1.0304558841628937E-6, 1.2394645269881283E-6], a=1.2, v=0.05, r=0.0)
    # “MouvCercle”
    # “Point_de_pass_2″
    # “Point_de_pass_3″

    movec(p[0.7071068000803379, 0.7071067995784731, 0.08000000010201744, -2.9024520981635957, -1.202235652075066, -5.149122323008E-7], p[1.9933919221160015E-10, 0.999999999718092, 0.08000000010201717, 2.2214411881580385, 2.2214417499998165, 1.454230456155269E-6], a=1.2, v=0.05, r=0.0)

    global pos = get_actual_tcp_pose()
    varmsg(pos,pos)

    Reply
  10. ben

    Hi Zacorbia,

    Thanks for your reply !

    Sorry for the mistake. I would say :

    - For a circular motion from A to B through midpoint C, with a blend radius of 0, we noticed that the robot never reaches its position and orientation. It’s always close to B but never B. Moreover the tool orientation during the motion from A to B is never the same from one motion to another…
    - We also noticed that for a waypoint P=p[x,y,z,ax,ay,az], if we execute a moveJ, the robot never reaches P but it is always close to P…
    - Is it possible to implement a function such as MoveC on the robot ?

    I want to add that our robot was calibrated.

    Regards
    Ben

    Reply
    1. zacopressadmin Post author

      Hi Ben

      Notice that the data provide for the robot is – repeatability – which is 0.1 mm. Repeatability means the robot has been at the location before which is the case for most Pick and Place application where the waypoints has been taught in advance.

      My experience is that the robot is good at drawing circle – see the example on this page.

      There is a Movec command – see the script manual.

      http://www.zacobria.com/pdf/universal-robots-scriptmanual-en-v-1-8.pdf

      Regards
      Zacobria

      Reply
  11. Ben

    Hi,

    I’ve an UR10 and I’m trying to make circular motion. I noticed two problems :

    - The robot doesn’t reach its target position even with a radius of 0. Indeed, it’s close to the target position but not exactly at the position…
    - The tool orientation during the motion change from one motion to another
    - I tried to use several linear motion to interpolate the circular trajectory but the program doesn’t load if the number of waypoins is beyond 300 !

    Please can you give explanations about this ? I really need to make the circular motion

    Reply
    1. zacopressadmin Post author

      Hi Ben

      Thanks for your question.

      A circle with a radius of exactly 0 is not a valid parameter.

      Using the build-in function for Circle Move – my experience is that the minimum radius is 5 mm. Is I need a circle below 5 mm I choose to rotate the tool head 360 degree which the UR can easy do as the joint can turn 720 degree in total.

      For the number of waypoint I need a copy of you program to test.

      Regards
      Zacobria

      Reply
  12. SJ Teo

    Hi Zacobria,

    We have a UR10 and was wondering how to draw a circle using the CircleMove function. We have only been able to draw a part of a circle using the CircleMove but not a whole one.
    What we have done so far to draw a circle is as follows:

    MoveP
    Waypoint_0
    CircleMove
    Waypoint_1
    Waypoint_2
    Waypoint_2
    CircleMove
    Waypoint_2
    Waypoint_0

    Another question is how do we set the tool orientation? We are looking to have the tool to be perpendicular with the circle but the turn speed of the tool has not been fast enough to turn together with the rest of the robot arm.

    Thanks for your time.

    Reply
    1. zacopressadmin Post author

      Hi Teo

      Thanks for your question.

      Your program looks good.

      To draw a full circle – it is made up of half circles.

      The robot needs a starting point which can be the top of the circle (north) – then a via point which can be the right side (east) of the circle and then an end point which can be the bottom (south) – which makes up a half circle.
      Then follow the same approach the previous end point can now be the starting point for the next half circle i.e. at the bottom (south) of the circle – then the via point can be set at left side (west) of the circle and the end point can be set at the top (north) of the circle and thereby draw a full circle.

      There is no command that can draw a full circle in one command.

      Instead of making true round circles you can also make elliptical or egg form circles – for example if the left via point (east) is set with a different radius than the radius from centre to start (north) – then it will become an elliptical shape.

      You have much more flexibility to make different patterns of circles when making them up of half circles.

      See also this example.

      http://www.zacobria.com/universal-robots-zacobria-forum-hints-tips-how-to/movep-process-move-circular-move/

      Regards
      Zacobria

      Reply
  13. Tom Svilans

    Hi,

    What is the crucial different between MoveP and MoveL commands? Why is the transition between them so jerky / sudden? I’ve been going over the forum but am still a little confused… Would really appreciate a bit of insight!

    Reply
    1. zacopressadmin Post author

      Hi Tom

      Thanks for your question.

      They are similar, MoveP is based on MoveL, but can also make circular moves.

      The jerk you mention might be caused by a different direction the robot is asked to take from the last end point to the next waypoint.

      Can you consider to insert a stopl() in between ? – for example stopl(1.0) or stopl(2.0) in order to smoothen the transition.

      Best Regards
      Zacobria
      Universal-Robots Distributor
      Singapore

      Reply
    1. zacopressadmin Post author

      Hi Rune

      Thanks for your question.

      Yes – the move does not need to be a full circle – and you can also make elliptical moves if the radius to the via point is different than the radius to the start or end point.

      Regards
      Lars

      Reply

Leave a Reply

Your email address will not be published. Required fields are marked *

You may use these HTML tags and attributes: <a href="" title=""> <abbr title=""> <acronym title=""> <b> <blockquote cite=""> <cite> <code> <del datetime=""> <em> <i> <q cite=""> <strike> <strong>