기본 강체 트리 모델 빌드
이 예제에서는 강체 트리 로봇 모델의 요소를 사용하여 5자유도 기본 로봇 팔을 빌드하는 방법을 보여줍니다. 이 예제에서 빌드하는 모델은 서보와 집적 회로 보드를 사용하는 일반적인 탁상용 로봇 팔을 표현합니다.
일반적인 상업용 로봇 세트에서 로봇 모델을 불러오기 위해 loadrobot
함수를 사용합니다. 이에 대한 예제는 미리 정의된 로봇 모델 불러오기 항목을 참조하십시오.
로봇에 대한 URDF 파일 또는 Simscape Multibody™ 모델이 있는 경우에는 importrobot
을 사용하여 강체 트리로 가져올 수 있습니다. 이에 대한 예제는 URDF 파일에서 로봇 가져오기 항목을 참조하십시오.
강체 요소 만들기
먼저 rigidBodyTree
로봇 모델을 만듭니다. 강체 트리 모델은 전체 로봇을 표현하며, 강체와 이들 강체를 연결하는 조인트로 구성됩니다. 로봇의 베이스는 세계 좌표를 정의하는 고정 프레임입니다. 첫 번째 바디를 추가하고 이 바디를 베이스에 연결합니다.
robot = rigidBodyTree("DataFormat","column"); base = robot.Base;
그런 다음, rigidBody
객체로 일련의 연결을 만듭니다. 로봇은 회전하는 베이스, 3개의 직각형 팔, 그리퍼로 구성됩니다.
rotatingBase = rigidBody("rotating_base"); arm1 = rigidBody("arm1"); arm2 = rigidBody("arm2"); arm3 = rigidBody("arm3"); gripper = rigidBody("gripper");
서로 다른 형태와 크기를 가진 각 강체에 대한 collision 객체를 만듭니다. collision 객체를 만들 때 좌표 프레임의 중심은 기본적으로 객체의 가운데에 맞춰집니다. 프레임이 z축을 따라 각 바디의 바닥쪽으로 이동하도록 Pose
속성을 설정합니다. 문제를 단순화하기 위해, 그리퍼를 구형으로 모델링합니다.
collBase = collisionCylinder(0.05,0.04); % cylinder: radius,length collBase.Pose = trvec2tform([0 0 0.04/2]); coll1 = collisionBox(0.01,0.02,0.15); % box: length, width, height (x,y,z) coll1.Pose = trvec2tform([0 0 0.15/2]); coll2 = collisionBox(0.01,0.02,0.15); % box: length, width, height (x,y,z) coll2.Pose = trvec2tform([0 0 0.15/2]); coll3 = collisionBox(0.01,0.02,0.15); % box: length, width, height (x,y,z) coll3.Pose = trvec2tform([0 0 0.15/2]); collGripper = collisionSphere(0.025); % sphere: radius collGripper.Pose = trvec2tform([0 -0.015 0.025/2]);
충돌 바디를 강체 객체에 추가합니다.
addCollision(rotatingBase,collBase) addCollision(arm1,coll1) addCollision(arm2,coll2) addCollision(arm3,coll3) addCollision(gripper,collGripper)
조인트 연결하기
각 강체는 회전 조인트를 사용하여 연결됩니다. 각 바디에 대해 rigidBodyJoint
객체를 만듭니다. x축을 직각형 팔 조인트의 회전 축으로 지정합니다. 그리퍼에 대해서는 y축을 지정합니다. 디폴트 축은 z축입니다.
jntBase = rigidBodyJoint("base_joint","revolute"); jnt1 = rigidBodyJoint("jnt1","revolute"); jnt2 = rigidBodyJoint("jnt2","revolute"); jnt3 = rigidBodyJoint("jnt3","revolute"); jntGripper = rigidBodyJoint("gripper_joint","revolute"); jnt1.JointAxis = [1 0 0]; % x-axis jnt2.JointAxis = [1 0 0]; jnt3.JointAxis = [1 0 0]; jntGripper.JointAxis = [0 1 0] % y-axis
jntGripper = rigidBodyJoint with properties: Type: 'revolute' Name: 'gripper_joint' JointAxis: [0 1 0] PositionLimits: [-3.1416 3.1416] HomePosition: 0 JointToParentTransform: [4x4 double] ChildToJointTransform: [4x4 double]
바디 간 조인트 연결의 변환을 설정합니다. 각 변환은 이전 강체 길이(z축)의 크기를 기준으로 합니다. 회전 중에 충돌을 방지하기 위해 x축에서의 팔 조인트를 오프셋합니다.
setFixedTransform(jnt1,trvec2tform([0.015 0 0.04])) setFixedTransform(jnt2,trvec2tform([-0.015 0 0.15])) setFixedTransform(jnt3,trvec2tform([0.015 0 0.15])) setFixedTransform(jntGripper,trvec2tform([0 0 0.15]))
로봇 조립하기
원래 베이스를 포함해 바디와 조인트 모두에 대한 객체 배열을 만듭니다. 각 조인트를 바디에 추가하고, 바디를 트리에 추가합니다. 각 단계를 시각화합니다.
bodies = {base,rotatingBase,arm1,arm2,arm3,gripper}; joints = {[],jntBase,jnt1,jnt2,jnt3,jntGripper}; figure("Name","Assemble Robot","Visible","on") for i = 2:length(bodies) % Skip base. Iterate through adding bodies and joints. bodies{i}.Joint = joints{i}; addBody(robot,bodies{i},bodies{i-1}.Name) show(robot,"Collisions","on","Frames","off"); drawnow; end
최종 트리 정보의 목록을 보기 위해 showdetails
함수를 호출합니다. 부모-자식 관계와 조인트 유형이 올바른지 확인합니다.
showdetails(robot)
-------------------- Robot: (5 bodies) Idx Body Name Joint Name Joint Type Parent Name(Idx) Children Name(s) --- --------- ---------- ---------- ---------------- ---------------- 1 rotating_base base_joint revolute base(0) arm1(2) 2 arm1 jnt1 revolute rotating_base(1) arm2(3) 3 arm2 jnt2 revolute arm1(2) arm3(4) 4 arm3 jnt3 revolute arm2(3) gripper(5) 5 gripper gripper_joint revolute arm3(4) --------------------
로봇 모델과 상호 작용하기
크기를 확인하기 위해 interactiveRigidBodyTree
객체를 사용하여 로봇 모델을 시각화합니다. 대화형 GUI를 사용하여 모델을 움직여 봅니다. 특정 바디를 선택하고 해당 바디의 조인트 위치를 설정할 수 있습니다. Robotics System Toolbox™와 함께 제공된 보다 세부적인 모델과 상호 작용하려면 미리 정의된 로봇 모델 불러오기 항목 또는 loadrobot
함수를 참조하십시오.
figure("Name","Interactive GUI") gui = interactiveRigidBodyTree(robot,"MarkerScaleFactor",0.25);
대화형 마커를 움직여 원하는 다양한 그리퍼 위치를 테스트합니다. GUI는 최적의 조인트 컨피규레이션을 생성하기 위해 역기구학을 사용합니다. 대화형 GUI에 대한 자세한 내용은 interactiveRigidBodyTree
객체를 참조하십시오.
다음 단계
MATLAB®에서 모델을 빌드했으므로 다양한 작업을 수행할 수 있습니다.
역기구학을 수행하여 목표 엔드 이펙터 위치를 기반으로 조인트 컨피규레이션을 구합니다. 모델 파라미터 외에 조준 제약 조건이나 카테시안 범위 또는 자세 타깃을 비롯한 추가적인 로봇 제약 조건을 지정합니다.
사다리꼴 속도 프로파일 궤적, B-스플라인 궤적, 다항식 궤적에 웨이포인트와 다른 여러 파라미터를 기반으로 궤적 생성을 생성합니다.
로봇 모델과 RRT(Rapidly-exploring Random Tree) 경로 플래너를 활용하여 매니퓰레이터 계획을 수행합니다.
로봇의 안전하고 효율적인 모션을 보장하기 위해 환경에 존재하는 장애물에 대해 충돌 감지을 수행합니다.