Skip to main content
Skip table of contents

CDRFLEx.movel

기능

로봇제어기에서 로봇을 작업 공간 안에서 목표 위치(pos)로 직선을 따라 이동시키기 위한 함수 이다.

인수

인수명자료형기본값설명

fTargetPos

float[6]

-

6개 축에 대한 목적 TCP 위치

fTargetVel

float[2]

-

선속도, 각속도

fTargetAcc

float[2]

-

선가속도, 각가속도

fTargetTime

float

0.f

도달 시간 [sec]

* time 지정 시, vel, acc를 무시하고 time 기준으로 처리

eMoveMode

enum.MOVE_MODE

MOVE_MODE_

ABSOLUTE

상수 및 열거형 정의 참조

eMoveReference

enum.MOVE_REFERENCE

MOVE_REFERENCE_BASE

상수 및 열거형 정의 참조

fBlendingRadius

float

0.f

blending시 radius

eBlendingType

enum.BLENDING_SPEED_TYPE

BLENDING_SPEED_TYPE_DUPLICATE

상수 및 열거형 정의 참조

알아두기

  • fTargetVel 에 하나의 인자를 입력한 경우(예를들어, fTargetVel ={30, 0}) 입력된 인자는 모션의 선속도에 대응되며, 각속도는 선속도에 비례하여 결정됩니다.
  • fTargetAcc 에 하나의 인자를 입력한 경우(예를들어, fTargetAcc ={60, 0}) 입력된 인자는 모션의 선가속도에 대응되며, 각가속도는 선가속도에 비례하여 결정됩니다.
  • fTargetTime 지정 시, fTargetVel, fTargetAcc 를 무시하고 fTargetTime 기준으로 처리됩니다.


주의

eBlendingTypeBLENDING_SPEED_TYPE_DUPLICATE이고 fBlendingRadius 0보다 큰 조건으로 후속 모션이 블렌딩 될 경우 선행모션의 잔여거리, 속도, 가속도로 결정되는 잔여모션시간이 후행모션의 모션시간보다 큰 경우 후행모션이 먼저 종료된 후 선행모션이 종료될 수 있습니다. 관련한 사항은 아래 이미지를 잠고하십시오.


리턴

설명

0

오류

1

성공

예제

CPP
// CASE 1
float x1[6] = { 559, 434.5, 651.5, 0, 180, 0 };
float tvel = { 50, 50 };
float tacc = { 100, 100 };
drfl.movel(x1, tvel, tacc);
// 속도 50(mm/sec), 가속도 100(mm/sec2)로 x1 위치로 이동

// CASE 2
float x1[6] = { 559, 434.5, 651.5, 0, 180, 0 };
float tTime = 5;
drfl.movel(x1, 0, 0, tTime);
// x1 위치로 5초의 도착시간을 가지고 이동

// CASE 3
float x1[6] = { 559, 434.5, 651.5, 0, 180, 0 };
float tvel = 50;
float tacc = 100;
drfl.movel(x1, tvel, tacc, 0, MOVE_MODE_RELATIVE, MOVE_REFERENCE_TOOL);
// 시작위치에서 Tool 좌표계 기준으로 x1 만큼의 상대위치로 이동
float x1[6] = { 559, 434.5, 651.5, 0, 180, 0 };
float x2[6] = { 559, 434.5, 251.5, 0, 180, 0 };
float tvel = 50;
float tacc = 100;
float blending_radius = 100;
drfl.movel(x1, tvel, tacc, 0, MOVE_MODE_ABSOLUTE, MOVE_REFERENCE_BASE, blending_radius);

JavaScript errors detected

Please note, these errors can depend on your browser setup.

If this problem persists, please contact our support.