Skip to content

C++ IndyDCP client

C++ IndyDCP clientIndyDCP Protocol 을 기반으로 Indy 를 제어할 수 있는 C++ class 입니다. 모든 관련 함수는 IndyDCPConnector.h 에 선언되어 있습니다.

설치

C++ IndyDCP client 의 소스파일과 프로젝트 파일은 다운로드 페이지에서 사용중인 Indy SW와 동일버전으로 다운로드 해주시기 바랍니다.

C++ IndyDCP clientWIndowsLinux 두 OS에서 사용할 수 있습니다. 윈도우 환경에서 실행시킬 경우 아래 경로의 Visual Studio 프로젝트를 여시면 됩니다.

  • /IndyDCPClientWindows/IndyDCPClientWindows.sln

Notes

Visual Studio에서 "precompiled header"와 관련된 에러가 발생할 경우 아래와 같이 관련 옵션을 해제하십시오. - 프로젝트 속성 페이지, "구성 속성 > C/C++ > 미리 컴파일된 헤더" 탭으로 이동 - "미리 컴파일된 헤더" 옵션을 "사용 안 함"으로 변경.

Socket 통신의 초기화와 종료

C++ IndyDCP client 를 사용하기 전, OS별로 아래와 같이 socket 통신을 사용하기 위한 라이브러리 초기화를 수행해야 합니다. Windows의 경우 별도의 종료 함수도 호출해주어야 합니다.

  • Windows
 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
// Winsock 라이브러리 "ws2_32.dll"를 링크
#pragma comment(lib,"ws2_32")

// WinSock 초기화
initWinSock();

///////////////////////////
// Indy 작업이 들어갈 부분 //
//////////////////////////

// WinSock 종료
cleanupWinSock();
  • Linux
1
2
3
4
5
6
7
#include <unistd.h>

///////////////////////////
// Indy 작업이 들어갈 부분 //
//////////////////////////

// 별도 종료 코드 없음.

Indy와의 연결 및 연결 해제

Indy 와의 모든 통신은 IndyDCPConnector.h 에 선언되어 있는 IndyDCPConnector 클래스를 통해 수행할 수 있습니다. IndyDCPConnector 객체를 초기화하기 위해서는, Indy 의 종류와 IP 주소를 입력해야 합니다. 사용 가능한 모든 로봇 종류는 NRMKIndy::Service::DCP namespace 안에 정의되어 있습니다.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
#include "IndyDCPConnector.h"
using namespace NRMKIndy::Service::DCP;

//Indy 초기화
IndyDCPConnector connector("로봇.IP를.여기에.입력", ROBOT_INDY7);

//Indy에 연결
connector.connect()

///////////////////////////
// Indy 작업이 들어갈 부분 //
//////////////////////////

//Indy 연결 해제
connector.disconnect()

C++ IndyDCP 명령어 리스트

아래는 IndyDCP 전체 명령어 중 일부에 대한 사용 예시들을 나타냅니다. 예시에 포함되지 않은 명령어는 전체 명령어 리스트에서 확인할 수 있으며 사용방법에 대해서는 다운받은 C++ IndyDCP 코드를 참고해주시기 바랍니다.

Note

모든 IndyDCPConnector 함수의 반환 값은 정수 에러 코드로 함수의 기능과는 관련이 없습니다. 요청한 값에 대한 반환은 참조자를 통해 반환합니다 (call-by-reference).

함수 기능
stopEmergency() 비상정지 실행
resetRobot() 로봇 리셋
setServoOnOff(const char * const servoVec)
setServoOnOff(const bool * const servoVec)
setServoOnOff(std::initializer_list servoVec)

servoVec 값에 따라 서보 On/Off
setBrakeOnOff(const char * const brakeVec)
setBrakeOnOff(const bool * const brakeVec)
setBrakeOnOff(std::initializer_list brakeVec)

brakeVec 값에 따라 브레이크 On/Off
stopMotion() 로봇 모션 중지
executeMoveCommand(const std::string & cmdName) Conty를 통해 티칭된 cmdName 이름을 가진 Move Command 실행
moveJointHome() 홈 포지션으로 이동
moveJointZero() 제로 포지션으로 이동
moveJointTo(const double * const qvec)
moveJointTo(std::initializer_list qvec)
모든 관절 각도를 qvec의 값으로 이동
moveJointBy(const double * const qvec)
moveJointBy(std::initializer_list qvec)
모든 관절 각도를 qvec의 값 만큼 상대적으로 이동
moveTaskTo(const double * const pvec)
moveTaskTo(std::initializer_list pvec)
로봇 엔드 이펙터를 pvec의 6 자유도 위치로 이동
moveTaskBy(const double * const pvec)
moveTaskBy(std::initializer_list pvec)
로봇 엔드 이펙터를 pvec 의 6 자유도 값 만큼 상대적으로 이동
startCurrProgram() 현재 로드된 로봇 프로그램 실행
pauseProgram() 현재 현재 실행중인 프로그램 일시정지
resumeProgram() 현재 일시정지된 프로그램 재개
stopProgram() 현재 프로그램 중지
startRegisteredDefaultProgram() 현재 등록된 기본 콘티 프로그램 실행
registerDefaultProgram(int idx) idx 1-10번 기본 프로그램 등록
getRegisteredDefaultProgram(int &ret) 현재 등록된 기본 프로그램 번호 요청
isRobotRunning(bool& ret) 로봇 소프트웨어의 동작 여부를 확인
isRobotReady(bool& ret) 로봇이 동작 가능한 상태인 지 확인
isEmergencyStopped(bool& ret) 로봇이 비상 정지 상태인 지 확인
isCollided(bool& ret) 로봇이 충돌 감지로 인해 정지되어 있는 지 확인
isErrorState(bool& ret) 로봇이 에러 상태인 지 확인
isMoveFinished(bool& ret) 로봇의 동작이 멈춘 상태인 지 확인
isBusy(bool& ret) 로봇이 움직이는 도중인 지 확인
isHome(bool& ret) 로봇이 홈 포지션에 있는 지를 확인
isZero(bool& ret) 로봇이 제로 포지션에 있는 지를 확인
isInResetting(bool& ret) 로봇이 리셋 도중인 지 확인
isDirectTeachingMode(bool& ret) 로봇이 직접교시 모드인 지 확인
isTeachingMode(bool& ret) 로봇이 교시 모드인 지 확인 (직접 교시, 조그)
isProgramRunning(bool& ret) 로봇이 동작 프로그램을 수행중인 지 확인
isProgramPaused(bool& ret) 로봇의 동작 프로그램이 일시정지 되었는 지 확인
isContyConnected(bool& ret) 로봇에 Conty 가 연결되었는 지 확인
changeToDirectTeachingMode() 로봇 직접교시 모드 진입
finishDirectTeachingMode() 로봇 직접교시 모드 종료
addJointWaypointSet(const double * const qvec)
addJointWaypointSet(std::initializer_list qvec)
관절 웨이포인트 추가
removeJointWaypointSet() 마지막 관절 웨이포인트를 제거
clearJointWaypointSet() 모든 관절 웨이포인트 제거
executeJointWaypointSet() 저장된 관절 웨이포인트로 모션 시작
addTaskWaypointSet(const double * const pvec)
addTaskWaypointSet(std::initializer_list pvec)
태스크 웨이포인트 추가
removeTaskWaypointSet() 태스크 웨이포인트 제거
clearTaskWaypointSet() 태스크 웨이포인트 제거
executeTaskWaypointSet() 저장된 태스크 웨이포인트 사이의 모션 시작
setDefaultTCP(const double * const tcpVec)
setDefaultTCP(std::initializer_list tcpVec)
기본 TCP값을 tcpVec 로 설정
resetDefaultTCP() 기본 TCP값 리셋
setTCPCompensation(const double * const tcpVec)
setTCPCompensation(std::initializer_list tcpVec)
TCP 보정값을 tcpVec 로 설정
resetTCPCompensation() TCP 보정값 리셋
setReferenceFrame(const double * const refFrameVec)
setReferenceFrame(std::initializer_list refFrameVec)
Reference 프레임 값을 refFrameVec 으로 설정
resetReferenceFrame() Reference 프레임 값 리셋
setCollisionDetectionLevel(int level) 충돌감지 민감도 레벨 설정 (1-5)
setJointBoundaryLevel(int level) JointMove 기본 속도/가속도 한계 레벨 설정 (1-9)
setTaskBoundaryLevel(int level) TaskMove 기본 속도/가속도 한계 레벨 설정 (1-9)
setJointBlendingRadius(double radius) JointMove 블랜딩 반경을 radius 값으로 설정
setTaskBlendingRadius(double radius) TaskMove 블랜딩 반경 radius 값으로 설정
setJointWaypointTime(double time) JointMove의 웨이포인트간 이동시간을 time 으로 설정
setTaskWaypointTime(double time) TaskMove의 웨이포인트간 이동시간을 time 으로 설정
getDefaultTCP(double * const ret) 기본 TCP값 요청
getTCPCompensation(double * const ret) TCP 보정값 요청
getReferenceFrame(double * const ret) Reference Frame 값 요청
getCollisionDetectionLevel(int &ret) 충돌감지 민감도 레벨 값 요청
getJointBoundaryLevel(int &ret) JointMove 기본 속도/가속도 한계 레벨값 요청
getTaskBoundaryLevel(int &ret) TaskMove 기본 속도/가속도 한계 레벨값 요청
getJointBlendingRadius(double &ret) JointMove 기본 블렌딩 반경값 요청
getTaskBlendingRadius(double &ret) TaskMove 기본 블렌딩 반경값 요청
getJointWaypointTime(double &ret) JointMove의 웨이포인트 간 이동시간 요청
getTaskWaypointTime(double &ret) TaskMvoe의 웨이포인트 간 이동시간 요청
getTaskBaseMode(int &ret) TaskMove 제어 기준 축 요청
getRobotRunningTime(double &ret) 로봇 초기화 이후 총 실행시간 요청
getControlMode(int &ret) 현재 로봇의 제어 모드 요청
getJointServoState(char * const ret)
getJointServoState(char * const retServo, char * const retBrake)
getJointServoState(bool * const retServo, bool * const retBrake)

각 관절 축의 Servo, Brake 상태 요청
getJointPosition(double * const ret) 현재 로봇의 Joint 각도 위치 요청
getJointVelocity(double * const ret) 현재 로봇의 Joint 각속도 요청
getTaskPosition(double * const ret) 현재 로봇의 Task 위치 요청
getTaskVelocity(double * const ret) 현재 로봇의 Task 속도 요청
getTorque(double * const ret) 현재 로봇의 토크 요청
getLastEmergencyInfo(int & retCode, int * const retIntArgs, double * const retDoubleArgs) 로봇의 가장 최근 Emergency 상태 정보 요청
getSmartDigitalInput(int idx, char & ret) idx 번 DI 채널의 값을 참조 변수인 ret 에 저장
getSmartDigitalInputs(char * const & ret) 모든 DI 값을 한번에 획득. 각 채널의 값들은 참조 변수 ret 의 각 bit에 나뉘어 저장
setSmartDigitalOutput(int idx, char val) idx 번 DO 채널에 val 의 값을 할당
setSmartDigitalOutputs(const char * const val) 모든 DO 채널에 값을 할당. 각 채널의 값들은 val의 각 bit 값으로 할당
getSmartAnalogInput(int idx, int & ret) idx 번 AI 채널의 값을 획득. 결과는 참조변수인 ret에 저장 (범위 0~10000)
setSmartAnalogOutput(int idx, int val) idx 번 AO 채널에 val 값을 할당 (범위 0-10000)
getRobotCanFTSensorRaw(int * const ret) 로봇 앤드툴 CAN포트에 연결된 FT 센서의 raw 데이터값 수신
getRobotCanFTSensorTransformed(double * const ret) 로봇 앤드툴 CAN포트에 연결된 FT 센서의 변환된 데이터값 수신
getCBCanFTSensorRaw(int * const ret) 컨트롤박스의 CAN포트에 연결된 FT 센서의 raw 데이터값 수신
getCBCanFTSensorTransformed(double * const ret) 컨트롤박스의 CAN포트에 연결된 FT 센서의 변환된 데이터값 수신
readDirectVariable(int type, int addr, void * ret) type 타입과 addr 주소를 가지는 직접변수 단일 값 읽기
readDirectVariables(int type, int addr, int len, void * ret) type 타입과 addr 주소를 가지는 직접변수를 len 길이만큼 연속 값 읽기
writeDirectVariable(int type, int addr, void * ptrVal) type 타입과 addr 주소를 가지는 직접변수에 ptrVal 값 단일 쓰기
writeDirectVariables(int type, int addr, int len, void * ptrVal) type 타입과 addr 주소를 가지는 직접변수에 ptrVal 값을 len 길이만큼 연속 값 쓰기

단위

  • 6 자유도 위치 는 3차원 위치를 나타내는 3 개의 double 값과(x, y, z), 3차원 회전을 나타내는 3개의 double 각도 값으로(θx, θy, θz) 구성, 회전은 z-y-x의 순서로 적용.
  • 위치와 각도의 단위는 각각 m, °.
  • 모든 관절 값은 ° 단위로 표시.

간단한 모션과 DIO 예제

이 장에서는 간단한 로봇 동작과 DIO 제어를 포함한 예제를 소개합니다. 명확한 예시를 위해, 로봇은 Indy7, IP 주소는 192.168.0.100 로 가정합니다.

Warning

코드를 실행할 경우 로봇이 움직입니다. 로봇 주변의 공간을 비워 주세요!

  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
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
#if defined (LINUX)
#include <unistd.h>
#elif defined (WINDOWS)
#pragma comment(lib,"ws2_32")   //Must Link Winsock Library "ws2_32.dll"
#endif

#include <stdio.h>
#include <iostream>
#include "IndyDCPConnector.h"
using namespace std;
using namespace NRMKIndy::Service::DCP;
IndyDCPConnector connector("192.168.0.100", ROBOT_INDY7); // set the robot ip

void WaitFinish(IndyDCPConnector& connector) {
    // Wait for motion finishing
    bool fin = false;
    do {
        #if defined (LINUX)
            sleep(0.5);
        #elif defined(WINDOWS)
            Sleep(500);
        #endif
        connector.isMoveFinished(fin); // check if motion finished
    } while (!fin);
}

int main(int argc, char* argv[])
{
#if defined(WINDOWS)
    initWinSock();
#endif
    cout << "Connecting to the robot" << endl;
    connector.connect();

    bool ready;
    connector.isRobotReady(ready);

    if (ready) {
        cout << "Robot is ready" << endl;

        cout << "Go to zero position" << endl;
        connector.moveJointZero();
        WaitFinish(connector);

        cout << "Go to home position" << endl;
        connector.moveJointHome();
        WaitFinish(connector);

        double q[6];
        cout << "Current joint values: " << endl;
        connector.getJointPosition(q);
        for(int i = 0;i<6;i++){ cout << q[i] << ","; }
        cout << endl;

        cout << "Rotate last joint by 10 degrees" << endl;
        connector.moveJointBy({ 0,0,0,0,0,10 });
        WaitFinish(connector);

        cout << "Move joints to the saved values" << endl;
        connector.moveJointTo(q);
        WaitFinish(connector);

        cout << "Move along waypoints" << endl;
        connector.moveJointWaypointSet({
            0, 0, 0, 0, 0, 0,
            0, -15, -90, 0, -75, 0,
            0, 0, 0, 0, 0, 0,
            0, 15, 90, 0, 75, 0
            });
        WaitFinish(connector);

        cout << "Current end-effector position:" << endl;
        double p[6];
        connector.getTaskPosition(p);
        for (int i = 0; i < 6; i++) { cout << p[i] << ","; }
        cout << endl;

        cout << "Move end-effector upward by 5 cm" << endl;
        connector.moveTaskBy({ 0,0,0.05,0,0,0 });
        WaitFinish(connector);

        cout << "Move end-effector to saved position" << endl;
        connector.moveTaskTo(p);
        WaitFinish(connector);

        char ret;
        cout << "Read DI 20: " << endl;
        connector.getSmartDigitalInput(20, ret);
        cout <<  ret << endl;

        cout << "Write DO 4 as HIGH";
        connector.setSmartDigitalOutput(4, 1);

        cout << "Disconnecting robot" << endl;
        connector.disconnect();
    }

#if defined(WINDOWS)
    cleanupWinSock(); // cleanup socket
#endif
}