구성하기
로봇 실행하기
IndySDK를 통해 작성된 컴포넌트 파일을 이용하여 로봇을 처음 작동시키려는 사용자들은 미리 작성된 컴포넌트 파일들을 통해 구동테스트를 수행하는 것이 좋습니다.
설치가 완료되었으면 개발환경이 설치된 PC (Windows)의 /neuromeka/NRMKFoundation/ 디렉토리에 있는 LeanDeployment 폴더를 아래 그림에서와 같이 STEP의 /home/user/release 경로에 복사하십시오.
참고
사용자는 컴포넌트 파일들을 개발 컴퓨터에서 원격서버 (컨트롤박스에 있는 STEP)로 복사할 때 윈도우 탐색기를 이용하거나 WinSCP와 같은 SFTP, SCP, FTP 클라이언트를 활용하여 SSH 전송을 수행할 수 있습니다.

복사를 완료한 후, PuTTY (또는 다른 SSH 클라이언트 도구)를 이용하여 STEP에 접속하여 아래 터미널 명령을 입력해주십시오.
- STEP에서 TaskManager 파일에 대한 실행권한 획득
| $ cd /home/user/release/LeanDeployment
$ chmod 777 *
|
- 아래와 같이 root 권한으로 TaskManager 실행시키십시오. 이 때 JSON 설정 파일 deployIndy.json 의 경로를 TaskManager의 인수로 기입해야 합니다.
| $ sudo ./TaskManager -j deployIndy7.json
|
- TaskManager가 실행되면 로봇의 전원이 켜지며 Indy Framework이 실행됩니다. 그리고 그림 2와 같이 터미널 창에 기본적인 콘솔로그 화면이 나타납니다.

TaskManager 실행 시 나타나는 콘솔 로거
- 이제 사용자는 로봇 (또는 가상로봇) 제어를 위해서 Conty (티치 펜던트) 를 사용할 수 있습니다.
참고
Indy Framework 실행파일인 TaskManager와 공유라이브러리 (.so 파일)에 대한 설명은 Indy Framework를 참고해 주시기 바랍니다.
JSON 설정파일
deployIndy7.json 은 Indy 구동 시 함께 실행 할 작업들을 구성하고 있는 JSON 파일입니다. Indy Framework에서의 JSON 설정파일과 약간의 차이가 있습니다. 아래 예시에서 볼 수 있듯이 3개의 작업들이 배치되어 있으며 각 작업들은 Params 의 요소로써 컴포넌트들을 포함하고 있습니다.
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41 | {
"TimerRate" : 4000, /*Hz*/
"HighRate" : 4000, /*Hz*/
"MediumRate" : 20, /*Hz*/
"LowRate" : 1, /*Hz*/
"Path" : "/home/user/release/LeanDeployment/",
"QueueHigh" :
[
{
"TaskName" : "Indy7ControlTask",
"SharedLib" : "Indy7ControlTask.so", // For real robot operation
// Use Indy7ControlTask_sim.so for simulation mode
"Params" :
{
"RobotModel" : "Indy7Model",
"JInterpolator" : "JointInterpolator6D",
"JController" : "JointController6D",
"TInterpolator" : "TaskInterpolatorIndy",
"TController" : "TaskController6D"
}
},
{
"TaskName" : "Indy6DLoggingTask",
"SharedLib" : "Indy6DLoggingTask.so"
}
],
"QueueMedium" :
[
{
"TaskName" : "Indy6DCadkitTask",
"SharedLib" : "Indy6DCadkitTask.so",
"Params" :
{
"RobotModel" : "Indy7Model"
}
}
]
}
|
IndySDK의 JSON 설정파일 구성 예시
- Path: 공유라이브러리 파일이 위치한 전역 경로를 나타냅니다. 예시와 같이 해당 경로에 공유라이브러리 파일들 (*.so) 및 컴포넌트파일(*.comp)들이 들어있는 Component 폴더가 포함되어 있어야 합니다.
- Queue: TaskManager에 의해 실행되는 실시간 태스크를 정의합니다.
- QueueHigh 는 4000Hz 실행주기를 가지며 ControlTask와 LoggingTask를 배치하였습니다.
- QueueMedium 는 20Hz 실행주기를 가지며 CadKitTask를 배치하였습니다.
- QueueLow 는 1Hz 실행주기를 가지며 사용하지 않습니다.
- ControlTask는 미리 빌드된 (혹은 사용자가 개발한) 5가지 컴포넌트 파일로 재구성됩니다.
- Params: ControlTask는 5가지 IndySDK 컴포넌트 파일로 구성됩니다.
- 컴포넌트 플러그인 파일 (*.comp)들은 Path 디렉토리 내의 Component 폴더에 위치해야 합니다.
- JSON 설정파일에 컴포넌트 플러그인 파일을 명시할 때 확장자 (*.comp)를 제외하고 파일명만 기입해야 합니다.
참고
libIndy6DControlTask.so 는 실제 로봇을 구동하는 태스크이며, libIndy6DControlTask_sim.so 는 시뮬레이션 상에서만 로봇을 구동하는 태스크 입니다. 사용목적에 따라 실제 로봇 혹은 시뮬레이션 모드를 바꿔가며 로봇을 실행할 수 있습니다.
주의
개발 된 제어 알고리즘을 시뮬레이션 환경에서 검증 후, 실제로봇에 적용하는 것이 좋습니다.
IndySDK 컴포넌트
IndySDK의 컴포넌트는 공유라이브러리 기반의 플러그인으로 IndySDK 개발환경을 통해 빌드됩니다. 기본적으로 IndySDK는 아래 다섯 유형의 컴포넌트 플러그인을 제공합니다.
|
|
|
|
|
로봇의 수학적 모델을 표현
로봇 기구학과 자코비안 계산
로봇 파라미터: Modified DH, inertia, TCP (tool center point)
|
|
|
관절별 지령토크 계산
현재 관절구성에서의 중력토크 계산
|
|
|
관절공간 웨이포인트 사이의 경로보간
최대속도, 가속도에 대한 경계값 설정
|
|
|
관절별 지령토크 계산
|
|
|
작업공간 웨이포인트 사이의 경로보간
최대속도, 가속도에 대한 경계값 설정
|
Indy Framework에는 상황별로 제어모드 (cmode)가 바뀌도록 구현되어 있습니다. 로봇이 준비상태일 땐 cmode는 0이며, 관절공간 제어를 할 때에는 cmode 1, 작업공간 제어를 할 때에는 cmode 2, 그리고 직접교시 모드일때는 중력보상 제어를 수행하며 cmode 는 3의 값을 가집니다. IndySDK를 통해 사용자가 컴포넌트를 수정하여 각 제어모드에 적용되는 제어기를 구현할 수 있습니다. 아래 표는 각 제어모드에서 호출되는 컴포넌트 함수를 나타냅니다.
제어모드 (cmode) |
Joint Trajectory Interpolation Component |
Joint Control Component |
Task Trajectory Interpolation Component |
Task Control Component |
준비 (0) |
- |
computeControlTorq |
- |
- |
조인트무브 (1) |
traj |
computeControlTorq |
- |
- |
태스크무브 (2) |
- |
- |
traj |
computeControlTorq |
직접교시 (3) |
- |
computeGravityTorq |
- |
- |
제어모드 별로 호출되는 컴포넌트 함수
각 컴포넌트는 IndySDK에서 제공하는 프로젝트 템플릿에서 구현할 수 있습니다. 컴포넌트별 템플릿에 포함된 로봇제어 관련 함수들에 대해서는 아래 설명을 참조하십시오.
1. Robot Model Component
Robot Model 컴포넌트 템플릿은 실제 로봇의 기구학적, 동역학적 수학모델을 포함하며 기구학적, 동역학적 정보를 획득하기 위한 API 함수들을 포함하고 있습니다. API들은 abstract Robot Model 클래스에 정의되어있기 때문에 사용자는 로봇 모델을 직접 정의하고 상속할 수 있습니다. 컴포넌트에 사용되는 API들은 목적에 따라 여섯개의 그룹으로 분류될 수 있습니다.
기능 |
설명 |
TCP & Weight |
로봇 TCP의 무게 (kg)와 위치에 대한 접근 |
Joint Home Position |
관절 공간에서 로봇의 홈 설정 (디폴트값 제로) |
Forward Kinematics |
로봇의 TCP 또는 목표 좌표(Ttarget)에 대한 위치 및 속도를
참조 좌표계(TReference)에 대해서 계산 |
Jacobian |
로봇의 현재배치에서 자코비안 행렬 및 자코비안 미분행렬을 계산 |
Joint Acceleration Computation |
역 기구학을 이용해서 관절 속도 및 가속도를 계산
선택적으로 자코비안 행렬, 자코비안 미분행렬, 작업공간 속도 및 가속도를 계산
|
Target & Reference Coordinate |
목표 좌표계 (Ttarget)의 위치를 로봇의 마지막 몸체에 대하여 계산
참조 좌표계 (TReference)의 위치를 전역 좌표계에 대해서 계산
|
Robot Model의 Abstract API는 아래 코드와 같습니다.
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50 | class AbstractRobot6D : public NRMKFoundation::IndySDK::IndyBase6D
{
public:
typedef Eigen::Matrix<int, JOINT_DOF, 1> StateVec; //!< Typedef of state vector
typedef NRMKFoundation::CompositeHTransformTaskPosition TaskPosition;
typedef NRMKFoundation::CompositeHTransformTaskVelocity TaskVelocity;
typedef Eigen::Matrix<double, 6, 1> TaskVec; //!< Typedef of task vector
typedef Eigen::Matrix<double, 6, 6> TaskJacobian; //!< Typedef of task matrix
public:
AbstractRobot6D() : NRMKFoundation::IndySDK::IndyBase6D();
virtual ~AbstractRobot6D();
// Tool Center Point & Weight
double & toolWeight();
double & toolXcom();
double & toolYcom();
double & toolZcom();
// Joint-space Home Position
JointVec & qhome();
virtual bool setJointHome() { qhome() << 0, 0, 0, 0, 0, 0; };
// Forward Kinematics
virtual void computeFK(TaskPosition & pos, TaskVelocity & vel) = 0;
virtual void computeFK(TaskPosition & pos) = 0;
// Jacobian Computation
virtual void computeJacobian( TaskPosition & pos, TaskVelocity & vel,
TaskJacobian & J, TaskJacobian & Jdot) = 0;
// Joint-space Acceleration Computation
virtual int computeJointAcc( TaskJacobian const & J, TaskJacobian const & Jdot,
TaskVec & velRef, TaskVec & accRef,
JointVec & qdotRef, JointVec & qddotRef) = 0;
virtual int computeJointAcc( TaskJacobian const & J, TaskJacobian const & Jdot,
TaskVec & accRef, JointVec & qddotRef) = 0;
// Set Target & Reference Coordinate
virtual void setTtarget( LieGroup::Rotation const & R,
LieGroup::Displacement const & r);
virtual void setTReference( LieGroup::Rotation const & R,
LieGroup::Displacement const & r);
};
|
6자유도 로봇에 대한 Abstract API
2. Joint Trajectory Interpolation Component
Joint Trajectory Interpolation 컴포넌트는 미리 정의된 웨이포인트를 모두 거치는 관절공간 궤적을 생성하기 위해서 사용됩니다. 궤적 생성 시 프레임워크에 의해 설정된 모든 경계조건을 만족시켜야 합니다. 컴포넌트에서 사용되는 API들은 다섯개의 그룹으로 분류되며 API들은 abstract API에 정의되어 있습니다. 여기서, DIM은 관절공간 웨이포인트의 차원을 나타내는 상수 입니다. 사용자는 abstract API를 상속하여 컴포넌트를 개발할 시 DIM의 값을 명시해야 합니다.
기능 |
설명 |
Set Trajectory Generation Conditions |
초기시간, 최고속도, 최고가속도 등 계산 될 궤적에 대한 조건을 설정 |
Set Waypoint List |
웨이포인트 배열에 대한 포인터를 매개변수로 받아 경로 설정 |
**Compute Trajectory** |
원하는 위치, 속도, 가속도를 시간을 매개변수로하여 생성
이 함수는 Indy Framework 내부에서 매 실시간 사이클 마다 호출되므로 구현 시 연산시간이 사이클 시간을 초과하지 않도록 주의해야 함.
|
Get Trajectory Specification |
궤적의 사양 및 특성 획득 |
Get Trajectory State |
목표위치 도달여부, 반복동작 횟수와 같은 궤적의 현재 상태를 획득 |
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35 | template<int DIM>
class AbstractJPathInterpolator
{
public:
typedef Eigen::Matrix<double, DIM, 1> VecType;
public:
AbstractJPathInterpolator() {}
virtual ~AbstractJPathInterpolator() {}
/* Setup predefined conditions for the trajectory */
virtual void setPeriod(double delt) = 0;
virtual void setInitialTime(double t0) = 0;
virtual void setTraj(double t0) = 0;
virtual void setupTraj(int mode) {}
virtual void setLoop(bool enable) {}
virtual void setBoundaryCondAll(const VecType & vel_max, const VecType & acc_max) = 0;
/* Setup waypoint list */
virtual void setPath(const VecType *path, int len, double * maxDeviation) = 0;
virtual void resetPath() {}
/* Compute the desired configuration at a time */
virtual void traj(double time, VecType & posDes, VecType & velDes, VecType & accDes) = 0;
/* Get specification of the trajectory */
virtual double getDuration() = 0;
virtual int getNTotalSegment() = 0;
virtual int getCurrentWaypoint() = 0;
/* Get the current status of the trajectory */
virtual bool isTargetReached() = 0;
virtual bool isTrajSetFailed() = 0;
virtual bool isLoop() { return false; }
};
|
Joint-space Trajectory Interpolator에 대한 Abstract API
3. Joint Control Component
Joint Controller 컴포넌트는 현재 로봇위치, 속도, 가속도 및 힘센서 값 등과 타겟 위치, 속도, 가속도를 입력으로 받아서 모든 관절에 대한 목표토크 값을 계산한 후 계산된 관절토크를 모터 드라이브로 전달합니다. Joint-space Controller의 API는 아래 표와 같이 세 가지 그룹으로 구분됩니다.
기능 |
설명 |
Configure Controller |
제어기의 내부 특성을 구성 |
Reset State |
적분에러와 같은 사용자가 정의한 내부 변수들을 재설정 |
**Compute Torque** |
로봇 관절에 적용될 토크 값 계산
이 함수는 Indy Framework 내부에서 매 실시간 사이클 마다 호출되므로 구현 시 연산시간이 사이클 시간을 초과하지 않도록 주의해야 함.
|
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24 | template<typename AbstractRobotType>
class AbstractJointController
{
public:
typedef AbstractRobotType ROBOT;
typedef typename ROBOT::JointVec JointVec;
public:
AbstractJointController() {}
virtual ~AbstractJointController() {}
/* Configure Controller */
virtual void setPeriod(double delt) {}
virtual void setPassivityMode(bool enable) {}
virtual void setGains(JointVec const & kp, JointVec const & kv, JointVec const & ki) {}
/* Reset Internal Status */
virtual void reset() {}
virtual void reset(int jIndex) {}
/* Controlled Torque Computation */
virtual int computeControlTorq(ROBOT & robot, JointVec const & qDesired, JointVec const & qdotDesired, JointVec const & qddotDesired, JointVec & torque) = 0;
virtual int computeGravityTorq(ROBOT & robot, JointVec & torque) = 0;
};
|
Joint-space Controller의 Abstract API
4. Task Trajectory Interpolation Component
Task Trajectory Interpolation 컴포넌트는 웨이포인트를 모두 거치는 작업공간 궤적을 생성하기 위해서 사용됩니다. 생성된 궤적은 프레임워크에 의해 설정된 모든 경계조건을 만족시켜야만 합니다. 컴포넌트에서 사용되는 API들은 다섯개의 그룹으로 분류되며 API들은 abstract API에 정의되어 있습니다.
기능 |
설명 |
Set Trajectory Generation Conditions |
초기시간, 최고속도, 최고가속도 등 계산 될 궤적에 대한 조건을 설정 |
Set Waypoint List |
웨이포인트 배열에 대한 포인터를 매개변수로 받아 경로 설정 |
**Compute Trajectory** |
원하는 위치, 속도, 가속도를 시간을 매개변수로하여 생성
이 함수는 Indy Framework 내부에서 매 실시간 사이클 마다 호출되므로 구현 시 연산시간이 사이클 시간을 초과하지 않도록 주의해야 함.
|
Get Trajectory Specification |
궤적의 사양 및 특성 획득 |
Get Trajectory State |
목표위치 도달여부, 반복동작 횟수와 같은 궤적의 현재 상태를 획득 |
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38 | class AbstractFPathInterpolator
{
public:
typedef NRMKFoundation::CompositeHTransformTaskPosition PosType;
typedef NRMKFoundation::CompositeHTransformTaskVelocity VelType;
typedef VelType AccType;
typedef Eigen::Matrix<double, 2, 1> VecType2D;
public:
AbstractFPathInterpolator() {}
virtual ~AbstractFPathInterpolator() {}
/* Setup predefined conditions for the trajectory */
virtual void setPeriod(double delt) = 0;
virtual void setInitialTime(double t0) = 0;
virtual void setTraj(double t0) = 0;
virtual void setupTraj(int mode) {}
virtual void setBoundaryCondAll(VecType2D const & vel_max, VecType2D const & acc_max) = 0;
virtual void setLoop(bool enable) {}
virtual void setReadyPos(PosType & pos) {}
/* Input the list of waypoints */
virtual void setPath(const PosType *path, const int len, double * maxDeviation, const int *dirAngle = NULL, bool simulCheck = false) = 0;
virtual void resetPath() {}
/* Compute the desired configuration at a time */
virtual void traj(double time, PosType & pos, VelType & vel, AccType & acc) = 0;
/* Get specification of the trajectory */
virtual double getDuration() = 0;
virtual int getNTotalSegment() = 0;
virtual int getCurrentWaypoint() = 0;
/* Check the status of the trajectory */
virtual bool isTargetReached() = 0;
virtual bool isTrajSetFailed() = 0;
virtual bool isLoop() { return false; }
};
|
Task-space Trajectory Interpolator의 Abstract API
5. Task Control Component
Task Controller 컴포넌트는 6차원의 위치, 속도, 가속도 및 힘센서 값 등을 입력으로 받아서 모든 관절에 대한 목표토크 값을 계산하여 계산 된 토크값은 모터 드라이브로 전달합니다. Task-space Controller의 API는 아래 표와 같이 세가지 그룹으로 구분됩니다.
기능 |
설명 |
Configure Controller |
제어기의 내부 특성을 구성 |
Reset State |
적분에러와 같은 사용자가 정의한 내부 변수들을 재설정 |
**Compute Torque** |
로봇 관절에 적용될 토크 값 계산
이 함수는 Indy Framework 내부에서 매 실시간 사이클 마다 호출되므로 구현 시 연산시간이 사이클 시간을 초과하지 않도록 주의해야 함.
|
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29 | template<typename AbstractRobotType>
class AbstractTaskController
{
public:
typedef AbstractRobotType ROBOT;
typedef typename ROBOT::JointVec JointVec;
typedef NRMKFoundation::CompositeHTransformTaskPosition TaskPosition;
typedef NRMKFoundation::CompositeHTransformTaskVelocity TaskVelocity;
typedef NRMKFoundation::CompositeHTransformTaskVelocity TaskAcceleration;
typedef Eigen::Matrix<double, 6, 1> TaskVec;
public:
AbstractTaskController() {}
virtual ~AbstractTaskController() {}
/* Configure Controller */
virtual void setPeriod(double delt) {}
virtual void setPassivityMode(bool enable) {}
virtual void setGains(TaskVec const & kp, TaskVec const & kv, TaskVec const & ki) {}
/* Reset Internal Status */
virtual void reset() {}
/* Controlled Torque Computation */
virtual int computeControlTorq(ROBOT & robot, TaskPosition const & pDesired,
TaskVelocity const & velDesired,
TaskAcceleration const & accDesired,
JointVec & torque) = 0;
};
|
Task-space Controller의 Abstract API