Skip to content

C++ IndyDCP3 클라이언트

C++에서 IndyDCP3 클라이언트를 사용하려면 아래 단계를 따르십시오. 이 가이드는 C++17 이상이 설정된 적절한 개발 환경을 갖추고 있다고 가정합니다.

설치 요구 사항

  • 프로젝트 구성 및 빌드를 위한 CMake가 필요합니다.
  • C++17 이상을 지원하는 C++ 컴파일러가 필요합니다.
  • IndyDCP3 라이브러리 파일 및 헤더가 필요합니다.

설치 방법

Linux

1. gRPC 설치

다음 gRPC 설치 가이드는 gRPC 공식 웹사이트에 기재된 내용을 요약한 것입니다. 자세한 내용은 grpc.io를 참조하세요.

로컬로 설치된 패키지를 보관할 디렉토리를 선택하십시오. 이 페이지는 환경 변수 MY_INSTALL_DIR이 이 디렉토리 경로를 보유하고 있다고 가정합니다. 아래 터미널 명령을 통해 디렉터리가 있는지 확인하십시오.

export MY_INSTALL_DIR=$HOME/.local

로컬 bin 폴더를 경로 변수에 추가하십시오.

mkdir -p $MY_INSTALL_DIR

예를 들어:

export PATH="$MY_INSTALL_DIR/bin:$PATH"

CMake 설치 버전 3.13 이상의 CMake가 필요합니다. 다음 지침에 따라 설치하십시오:

sudo apt install -y cmake
CMake 버전을 확인하십시오:
cmake --version

리눅스에서 시스템 전체 CMake 버전이 오래된 경우가 있습니다. 로컬 설치 디렉토리에 최신 버전을 설치하려면 다음 명령을 사용하십시오.

wget -q -O cmake-linux.sh https://github.com/Kitware/CMake/releases/download/v3.19.6/cmake-3.19.6-Linux-x86_64.sh
sh cmake-linux.sh -- --skip-license --prefix=$MY_INSTALL_DIR
rm cmake-linux.sh

기타 필요한 도구 설치 gRPC를 빌드하는 데 필요한 기본 도구를 설치하십시오:

$ sudo apt install -y build-essential autoconf libtool pkg-config

grpc 저장소 및 하위 모듈 클론:

$ git clone --recurse-submodules -b v1.59.0 --depth 1 --shallow-submodules https://github.com/grpc/grpc

gRPC 및 프로토콜 버퍼 빌드 및 설치

gRPC 애플리케이션은 종종 서비스 정의 및 데이터 직렬화를 위해 예제 코드에서와 같이 프로토콜 버퍼를 사용합니다. gRPC 및 프로토콜 버퍼를 빌드하고 로컬로 설치하려면 다음 명령을 실행하십시오:

cd grpc
mkdir -p cmake/build
pushd cmake/build
cmake -DgRPC_INSTALL=ON \
      -DgRPC_BUILD_TESTS=OFF \
      -DCMAKE_INSTALL_PREFIX=$MY_INSTALL_DIR \
      ../..
make -j 4
make install
popd

Note

전역 설치 후 gRPC를 제거하는 간단한 방법이 없기 때문에 CMAKE_INSTALL_PREFIX를 적절히 설정하여 gRPC를 로컬에 설치하는 것이 강력히 권장됩니다.

2. 예제 다운로드 및 빌드

예제 저장소 클론

git clone https://github.com/neuromeka-robotics/neuromeka-package.git

C++ 폴더로 이동

cd neuromeka-package/cpp/

빌드 디렉토리 생성 및 이동

mkdir build && cd build

CMake 구성 실행 및 예제 빌드

cmake -DBUILD_PROTO=OFF ..
cmake --build .
.proto 파일을 다시 빌드해야 하는 경우 -DBUILD_PROTO=ON을 설정하십시오. build_proto 실행 파일이 생성됩니다. 이 파일을 실행한 후 생성된 proto 파일은 proto/cpp_generated 폴더에 위치합니다.

Windows

이 설정에는 Visual Studio Code를 사용하는 것을 권장합니다.

1. 환경 설정

Visual Studio Code 설치 - 다음 확장 프로그램 설치: C/C++, C/C++ 확장 팩 및 CMake 도구.

vs_BuildTools 설치 - BuildTools 옵션에서 C++를 사용한 데스크톱 개발 및 Visual Studio 확장 개발을 선택하십시오.

2. gRPC 설치

모든 준비가 완료되면 개발자 명령 프롬프트를 열고 다음 명령을 실행하십시오:

git clone -b v1.59.0 https://github.com/grpc/grpc
cd grpc
git submodule update --init

빌드 폴더 생성

cd cmake
mkdir build
cd build

CMake를 사용하여 구성 및 빌드

cmake -G "Visual Studio 17 2022" -DCMAKE_BUILD_TYPE=Release -DCMAKE_CXX_STANDARD=17 -DBUILD_SHARED_LIBS=OFF -DABSL_PROPAGATE_CXX_STD=ON -DgRPC_INSTALL=ON -DgRPC_BUILD_TESTS=OFF -DCMAKE_INSTALL_PREFIX=..\..\..\install ../..
설치 경로는 "-DCMAKE_INSTALL_PREFIX=\<your path>를 사용하여 설정할 수 있습니다.

gRPC 빌드 및 설치

cmake --build . --config Release --target install

3. 예제 다운로드 및 빌드

예제 저장소 클론

git clone https://github.com/neuromeka-robotics/neuromeka-package.git

Visual Studio Code 열고 neuromeka-package/cpp/ 폴더 열기 .vscode 폴더의 settings.json으로 빌드를 구성하십시오. .proto 파일을 다시 빌드해야 하는 경우 -DBUILD_PROTO=ON으로 설정하십시오. build_proto 실행 파일이 생성됩니다.

그런 다음 CMakeList.txt를 수정하십시오. 다음 줄을 변경하여 grpc 설치 디렉토리를 가리키도록 하십시오.

set(absl_DIR "E:/Example/install/lib/cmake/absl")
set(utf8_range_DIR "E:/Example/install/lib/cmake/utf8_range")
set(protobuf_DIR "E:/Example/install/cmake")
set(gRPC_DIR "E:/Example/install/lib/cmake/grpc")

Visual Studio Code에서 Ctrl+Shift+P를 누르거나 보기 -> 명령 팔레트로 이동하여 명령 팔레트를 열고 다음 명령을 선택하십시오: - CMake: Scan for kits: 컴퓨터에서 컴파일러를 검색합니다. - CMake: Select a kit: 특정 컴파일러(예: Visual Studio Build Tools 2022 Release - amd64)를 선택합니다.

작업이 완료되면 왼쪽 하단의 빌드 버튼을 누르십시오.


IndyDCP3 사용

클라이언트 개체를 생성하려면 IndyDCP3 라이브러리에서 IndyDCP3 클래스 헤더를 포함하고 로봇의 IP 주소로 초기화하십시오.

#include "indydcp3.h"

int main() {
    IndyDCP3 indy("192.168.xxx.xxx");

    // indy 객체를 사용하여 로봇과 상호작용...
    return 0;
}
  • 192.168.xxx.xxx: 로봇 컨트롤러의 IP 주소.

메서드 및 함수

IndyDCP3 객체를 사용하여 호출할 수 있는 프로토콜 함수 목록은 아래에 나와 있습니다. 각 함수의 사용 방법 및 입출력 예제를 참조하세요.

실시간 데이터 수집 함수

로봇의 현재 모션 상태, 제어 데이터, 상태, 서보 모터 상태, 오류 정보 및 프로그램 상태를 검색할 수 있습니다.

메서드 설명
get_robot_data() 로봇 상태 데이터
get_control_state() 제어 상태
get_motion_data() 모션 데이터
get_servo_data() 서보 데이터
get_violation_data() 오류 데이터
get_program_data() 로봇 프로그램 데이터

get_robot_data()

Nrmk::IndyFramework::ControlData control_data;
bool is_success = indy.get_robot_data(control_data);
if (is_success) {
    // control_data 처리
}
{
  'running_mins': 6,
  'running_secs': 11,
  'op_state': 5,
  'sim_mode': true,  
  'ref_frame': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
  'tool_frame': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
  'running_hours': 0
}
  • running_hours:

로봇 작동 시간 - running_mins: 로봇 작동 분 - running_secs: 로봇 작동 초 - op_state: OpState 클래스에 정의된 로봇 상태 - OpState: SYSTEM_OFF(0), SYSTEM_ON(1), VIOLATE(2), RECOVER_HARD(3), RECOVER_SOFT(4), IDLE(5), MOVING(6), TEACHING(7), COLLISION(8), STOP_AND_OFF(9), COMPLIANCE(10), BRAKE_CONTROL(11), SYSTEM_RESET(12), SYSTEM_SWITCH(13), VIOLATE_HARD(15), MANUAL_RECOVER(16), TELE_OP(17)

get_control_state()

Nrmk::IndyFramework::ControlData control_data;
bool is_success = indy.get_control_state(control_data);
if (is_success) {
    // 관절 위치에 접근
    for (int i = 0; i < control_data.q_size(); i++) {
        float joint_position = control_data.q(i);
    }
}
{
  'q': [...],
  'qdot': [...],
  'qddot': [...],
  'qdes': [...],
  'qdotdes': [...],
  'qddotdes': [...],
  'p': [...],
  'pdot': [...],
  'pddot': [...],
  'pdes': [...],
  'pdotdes': [...],
  'pddotdes': [...],
  'tau': [...],
  'tau_act': [...],
  'tau_ext': [...],
}
  • q, qdot, qddot: 각 관절의 현재 위치(도), 속도(도/초) 및 가속도(도/초²)
  • qdes, qdotdes, qddotdes: 각 관절의 목표 위치(도), 속도(도/초) 및 가속도(도/초²)
  • p, pdot, pddot: 현재 작업 공간 자세 위치(mm), 속도(mm/초) 및 가속도(mm/초²)
  • pdes, pdotdes, pddotdes: 목표 작업 공간 자세 위치(mm), 속도(mm/초) 및 가속도(mm/초²)
  • tau, tau_act, tau_ext: 각 관절의 현재 입력 토크, 실제 토크 및 외부 토크(Nm)

get_servo_data()

Nrmk::IndyFramework::ServoData servo_data;
bool is_success = indy.get_servo_data(servo_data);
if (is_success) {
    std::vector<float> temperatures = servo_data.temperatures();
}
{
  'status_codes': ['0x1237', '0x1237', '0x1237', '0x1237', '0x1237', '0x1237'],
  'temperatures': [0.0, 0.0, 0.0, 0.0, 0.0, 0.0],
  'voltages': [48.0, 48.0, 48.0, 48.0, 48.0, 48.0],
  'currents': [3.4812942e-18,
              26.195215,
              26.963966,
              0.12320003,
              0.55777645,
              4.536144e-05],
  'servo_actives': [true, true, true, true, true, true],
  'brake_actives': [false, false, false, false, false, false]
 }
  • status_codes: 각 관절 서보의 상태 코드(CiA402)
  • temperatures: 각 관절 서보의 온도
  • voltages: 각 관절 서보의 전압
  • currents: 각 관절 서보의 전류
  • servo_actives: 각 관절 서보의 활성화 상태(true/false)
  • brake_actives: 각 관절 서보의 브레이크 활성화 상태(true/false)

get_violation_data()

Nrmk::IndyFramework::ViolationData violation_data;
bool is_success = indy.get_violation_data(violation_data);
if (is_success) {
    int j_index = violation_data.j_index();
}
{
  'j_index': 3,
  'i_args': [2],
  'f_args': [0.03445887],
  'violation_str': 'Collision Detected: joint (4/6), Error threshold , val 0.0345',
  'violation_code': '0'
}
  • j_index: 위반이 발생한 관절의 인덱스
  • i_args: 위반에 대한 정수 정보
  • f_args: 위반에 대한 부동 소수점 정보
  • violation_str: 오류 메시지

get_program_data()

Nrmk::IndyFramework::ProgramData program_data;
bool is_success = indy.get_program_data(program_data);
if (is_success) {
    std::string program_name = program_data.program_name();
}
{
  'program_name': 'ProgramScripts/',
  'program_state': 0,
  'cmd_id': 0,
  'sub_cmd_id': 0,
  'running_hours': 0,
  'running_mins': 0,
  'running_secs': 0,
  'program_alarm': '',
  'program_annotation': ''
}   
  • program_name: 현재 실행 중인 프로그램 파일의 이름
  • program_state: 프로그램 실행 상태
    • ProgramState: IDLE (0), RUNNING (1), PAUSING (2), STOPPING (3)

I/O 장치 관련 기능

I/O 장치 기능은 디지털 및 아날로그 I/O, 엔드 툴 I/O 및 센서와 같은 다양한 로봇 하드웨어 구성 요소와 상호 작용하는 데 사용됩니다.

메서드 설명
get_di(DigitalList &data) IO 보드 DI 데이터를 검색합니다
`get_do(Digital

List &data)| IO 보드 DO 데이터를 검색합니다 | |set_do(const DigitalList &data)| IO 보드 DO 데이터를 설정합니다 | |get_ai(AnalogList &data)| IO 보드 AI 데이터를 검색합니다 | |get_ao(AnalogList &data)| IO 보드 AO 데이터를 검색합니다 | |set_ao(const AnalogList &data)| IO 보드 AO 데이터를 설정합니다 | |get_endtool_di(EndtoolSignalList &data)| 엔드 툴 DI 데이터를 검색합니다 | |get_endtool_do(EndtoolSignalList &data)| 엔드 툴 DO 데이터를 검색합니다 | |set_endtool_do(const EndtoolSignalList &data)| 엔드 툴 DO 데이터를 설정합니다 | |get_endtool_ai(AnalogList &data)| 엔드 툴 AI 데이터를 검색합니다 | |get_endtool_ao(AnalogList &data)| 엔드 툴 AO 데이터를 검색합니다 | |get_device_info(DeviceInfo &data)| 장치 정보를 검색합니다 | |get_ft_sensor_data(FTSensorData &data)` | 엔드 툴 F/T 센서 데이터를 검색합니다 |

get_di() 예제

Nrmk::IndyFramework::DigitalList di_data;
bool is_success = indy.get_di(di_data);
if (is_success) {
    for (int i = 0; i < di_data.signals_size(); ++i) {
        std::cout << "DI " << i << " 주소: " << di_data.signals(i).address()
                  << ", 상태: " << di_data.signals(i).state() << std::endl;
    }
}

set_do() 예제

Nrmk::IndyFramework::DigitalList do_signal_list;
auto *do_signal = do_signal_list.add_signals();
do_signal->set_address(1);
do_signal->set_state(Nrmk::IndyFramework::DigitalState::ON);

bool is_success = indy.set_do(do_signal_list);
if (is_success) {
    std::cout << "DO 설정 성공." << std::endl;
} else {
    std::cerr << "DO 설정 실패." << std::endl;
}

get_ai() 예제

Nrmk::IndyFramework::AnalogList ai_data;
bool is_success = indy.get_ai(ai_data);
if (is_success) {
    for (int i = 0; i < ai_data.signals_size(); ++i) {
        std::cout << "AI " << i << " 주소: " << ai_data.signals(i).address()
                  << ", 전압: " << ai_data.signals(i).voltage() << std::endl;
    }
}

모션 명령 함수

모션 명령 함수를 사용하면 로봇의 움직임을 제어할 수 있으며, 특정 위치로 이동하거나 복잡한 모션 경로를 실행할 수 있습니다.

메서드 설명
stop_motion(StopCategory stop_category) 지정된 정지 범주에 따라 모션을 정지시킵니다
move_home() 로봇을 홈 위치로 이동합니다
movej(const std::vector<float> jtarget, const int base_type, const int blending_type, const float blending_radius, const float vel_ratio, const float acc_ratio, const bool const_cond, const int cond_type, const int react_type, DCPDICond di_condition, DCPVarCond var_condition, const bool teaching_mode) 로봇을 지정된 관절 대상 위치로 이동합니다
movel(const std::array<float, 6> ttarget, const int base_type, const int blending_type, const float blending_radius, const float vel_ratio, const float acc_ratio, const bool const_cond, const int cond_type, const int react_type, DCPDICond di_condition, DCPVarCond var_condition, const bool teaching_mode) 로봇을 지정된 선형 대상 위치로 이동합니다
movec(const std::array<float, 6> tpos1, const std::array<float, 6> tpos2, const float angle, const int setting_type, const int move_type, const int base_type, const int blending_type, const float blending_radius, const float vel_ratio, const float acc_ratio, const bool const_cond, const int cond_type, const int react_type, DCPDICond di_condition, DCPVarCond var_condition, const bool teaching_mode) 로봇을 원형 경로를 따라 이동시킵니다
start_teleop(TeleMethod method) 원격 제어 모드를 시작합니다
stop_teleop() 원격 제어 모드를 종료합니다

경고

모션 명령을 사용할 때는 주의해야 합니다. 명령이 성공적으로 적용되면 로봇이 즉시 움직이기 때문입니다. 펜던트를 통해 로봇을 사용할 때는 사용자가 터치 버튼을 누르고 있는 동안에만 움직일 수 있지만, API를 사용할 때는 프로그램 명령을 통해 움직일 수 있으므로 항상 충돌을 일으킬 수 있는 물체가 없는지 확인하십시오. 특히, 높은 속도 또는 가속도를 설정할 때는 로봇이 예상보다 빠르게 움직일 수 있으므로 안전에 유의해야 합니다.

stop_motion() 예제

이 함수는 지정된 정지 범주에 따라 로봇의 모션을 정지시킵니다.

StopCategory stop_category = StopCategory::SMOOTH_BRAKE;
bool is_success = indy.stop_motion(stop_category);
if (is_success) {
    std::cout << "모션이 성공적으로 정지되었습니다." << std::endl;
} else {
    std::cerr << "모션 정지 실패." << std::endl;
}

move_home() 예제

이 함수는 로봇을 사전 정의된 홈 위치로 이동시킵니다.

bool is_success = indy.move_home();
if (is_success) {
    std::cout << "로봇이 홈 위치로 성공적으로 이동되었습니다." << std::endl;
} else {
    std::cerr << "로봇을 홈 위치로 이동 실패." << std::endl;
}

movej() 예제

이 함수는 로봇을 지정된 관절 대상 위치로 이동시킵니다.

std::vector<float> target_joints = {0.0, 0.0, -90.0, 0.0, -90.0, 0.0};

bool is_success = indy.movej(target_joints);
if (is_success) {
    std::cout << "MoveJ 명령이 성공적으로 실행되었습니다." << std::endl;
} else {
    std::cerr << "MoveJ 명령 실패." << std::endl;
}

movel() 예제

이 함수는 작업 공간의 지정된 선형 대상 위치로 로봇을 이동시킵니다.

std::array<float, 6> target_pose = {350.0, -186.5, 522.0, -180.0, 0.0, 180.0};

bool is_success = indy.movel(target_pose);
if (is_success) {
    std::cout << "MoveL 명령이 성공적으로 실행되었습니다." << std::endl;
} else {
    std::cerr << "MoveL 명령 실패." << std::endl;
}

movec() 예제

이 함수는 두 개의 지정된 작업 공간 위치를 통과하는 원형 경로를 따라 로봇을 이동시킵니다.

std::array<float, 6> t_pos1 = {241.66, -51.11, 644.20, 0.0, 180.0, 23.3};
std::array<float, 6> t_pos2 = {401.53, -47.74, 647.50, 0.0, 180.0, 23.3};
float angle = 720.0;

bool is_success = indy.movec(tpos1, tpos2, angle);
if (is_success) {
    std::cout << "원형 이동이 성공적으로 실행되었습니다." << std::endl;
} else {
    std::cerr << "원형 이동 실패." << std::endl;
}

start_teleop() 예제

이 함수는 지정된 방법으로 원격 제어 모드를 시작합니다.

TeleMethod method = TeleMethod::TELE_JOINT_RELATIVE;
bool is_success = indy.start_teleop(method);
if (is_success) {
    std::cout << "원격 제어 모드가 성공적으로 시작되었습니다." << std::endl;
} else {
    std::cerr << "원격 제어 모드 시작 실패." << std::endl;
}

stop_teleop() 예제

이 함수는 원격 제어 모드를 종료합니다.

bool is_success = indy.stop_teleop();
if (is_success) {
    std::cout << "원격 제어 모드가 성공적으로 종료되었습니다." << std::endl;
} else {
    std::cerr << "원격 제어 모드 종료 실패." << std::

endl;
}

변수 처리 함수

IndyDCP3 C++ API는 부울, 정수, 부동 소수점, 관절 위치(JPos) 및 작업 위치(TPos) 변수와 같은 다양한 유형의 변수를 처리하는 여러 함수를 제공합니다. 이러한 변수는 로봇과 외부 장치 간에 정보를 교환하는 데 사용할 수 있습니다.

메서드 설명
get_bool_variable(std::vector<BoolVariable> &variables) Bool 유형 변수를 검색합니다
get_int_variable(std::vector<IntVariable> &variables) 정수형 변수를 검색합니다
get_float_variable(std::vector<FloatVariable> &variables) 부동 소수점 변수를 검색합니다
get_jpos_variable(std::vector<JPosVariable> &variables) JPos 유형 변수를 검색합니다
get_tpos_variable(std::vector<TPosVariable> &variables) TPos 유형 변수를 검색합니다
set_bool_variable(const std::vector<BoolVariable> &variables) Bool 유형 변수를 설정합니다
set_int_variable(const std::vector<IntVariable> &variables) 정수형 변수를 설정합니다
set_float_variable(const std::vector<FloatVariable> &variables) 부동 소수점 변수를 설정합니다
set_jpos_variable(const std::vector<JPosVariable> &variables) JPos 유형 변수를 설정합니다
set_tpos_variable(const std::vector<TPosVariable> &variables) TPos 유형 변수를 설정합니다

get_bool_variable() 예제

이 함수는 로봇에서 Bool 유형 변수의 현재 값을 검색합니다.

std::vector<Nrmk::IndyFramework::BoolVariable> bool_vars;
bool is_success = indy.get_bool_variable(bool_vars);
if (is_success) {
    std::cout << "부울 변수가 성공적으로 검색되었습니다." << std::endl;
    for (const auto &var : bool_vars) {
        std::cout << "주소: " << var.addr() << ", 값: " << var.value() << std::endl;
    }
} else {
    std::cerr << "부울 변수 검색 실패." << std::endl;
}

get_int_variable() 예제

이 함수는 로봇에서 정수형 변수의 현재 값을 검색합니다.

std::vector<Nrmk::IndyFramework::IntVariable> int_vars;
bool is_success = indy.get_int_variable(int_vars);
if (is_success) {
    std::cout << "정수형 변수가 성공적으로 검색되었습니다." << std::endl;
    for (const auto &var : int_vars) {
        std::cout << "주소: " << var.addr() << ", 값: " << var.value() << std::endl;
    }
} else {
    std::cerr << "정수형 변수 검색 실패." << std::endl;
}

get_float_variable() 예제

이 함수는 로봇에서 부동 소수점 변수의 현재 값을 검색합니다.

std::vector<Nrmk::IndyFramework::FloatVariable> float_vars;
bool is_success = indy.get_float_variable(float_vars);
if (is_success) {
    std::cout << "부동 소수점 변수가 성공적으로 검색되었습니다." << std::endl;
    for (const auto &var : float_vars) {
        std::cout << "주소: " << var.addr() << ", 값: " << var.value() << std::endl;
    }
} else {
    std::cerr << "부동 소수점 변수 검색 실패." << std::endl;
}

get_jpos_variable() 예제

이 함수는 로봇에서 관절 위치(JPos) 유형 변수의 현재 값을 검색합니다.

std::vector<Nrmk::IndyFramework::JPosVariable> jpos_vars;
bool is_success = indy.get_jpos_variable(jpos_vars);
if (is_success) {
    std::cout << "JPos 변수가 성공적으로 검색되었습니다." << std::endl;
    for (const auto &var : jpos_vars) {
        std::cout << "주소: " << var.addr() << ", JPos: ";
        for (const auto &jpos : var.jpos()) {
            std::cout << jpos << " ";
        }
        std::cout << std::endl;
    }
} else {
    std::cerr << "JPos 변수 검색 실패." << std::endl;
}

get_tpos_variable() 예제

이 함수는 로봇에서 작업 위치(TPos) 유형 변수의 현재 값을 검색합니다.

std::vector<Nrmk::IndyFramework::TPosVariable> tpos_vars;
bool is_success = indy.get_tpos_variable(tpos_vars);
if (is_success) {
    std::cout << "TPos 변수가 성공적으로 검색되었습니다." << std::endl;
    for (const auto &var : tpos_vars) {
        std::cout << "주소: " << var.addr() << ", TPos: ";
        for (const auto &tpos : var.tpos()) {
            std::cout << tpos << " ";
        }
        std::cout << std::endl;
    }
} else {
    std::cerr << "TPos 변수 검색 실패." << std::endl;
}

set_bool_variable() 예제

이 함수는 로봇의 Bool 유형 변수를 설정합니다.

std::vector<Nrmk::IndyFramework::BoolVariable> bool_vars;

Nrmk::IndyFramework::BoolVariable var1;
var1.set_addr(1);
var1.set_value(true);
bool_vars.push_back(var1);

bool is_success = indy.set_bool_variable(bool_vars);
if (is_success) {
    std::cout << "부울 변수가 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "부울 변수 설정 실패." << std::endl;
}

set_int_variable() 예제

이 함수는 로봇의 정수형 변수를 설정합니다.

std::vector<Nrmk::IndyFramework::IntVariable> int_vars;

Nrmk::IndyFramework::IntVariable var1;
var1.set_addr(2);
var1.set_value(42);
int_vars.push_back(var1);

bool is_success = indy.set_int_variable(int_vars);
if (is_success) {
    std::cout << "정수형 변수가 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "정수형 변수 설정 실패." << std::endl;
}

set_float_variable() 예제

이 함수는 로봇의 부동 소수점 변수를 설정합니다.

std::vector<Nrmk::IndyFramework::FloatVariable> float_vars;

Nrmk::IndyFramework::FloatVariable var1;
var1.set_addr(3);
var1.set_value(3.14f);
float_vars.push_back(var1);

bool is_success = indy.set_float_variable(float_vars);
if (is_success) {
    std::cout << "부동 소수점 변수가 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "부동 소수점 변수 설정 실패." << std::endl;
}

set_jpos_variable() 예제

이 함수는 로봇의 관절 위치(JPos) 유형 변수를 설정합니다.

std::vector<Nrmk::IndyFramework::JPosVariable> jpos_vars;

Nrmk::IndyFramework::JPosVariable var1;
var1.set_addr(1);
var1.add_jpos(0.0f);
var1.add_jpos(0.0f);
var1.add_jpos(-90.0f);
var1.add_jpos(0.0f);
var1.add_jpos(-90.0f);
var1.add_jpos(0.0f);
jpos_vars.push_back(var1);

bool is_success = indy.set_jpos_variable(jpos_vars);
if (is_success) {
    std::cout << "JPos 변수가 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "JPos 변수 설정 실패." << std::endl;
}

set_tpos_variable() 예제

이 함수는 로봇의 툴 위치(TPos) 유형 변수를 설정합니다.

std::vector<Nrmk::IndyFramework::TPosVariable> tpos_vars;

Nrmk::IndyFramework::TPosVariable var1;
var1.set_addr(1);
var1.add_tpos(350.0f);
var1.add_tpos(-186.5f);
var1.add_tpos(522.0f);
var1.add_tpos(-180.0f);
var1.add_tpos(0.0f);
var1.add_tpos(180.0f);
tpos_vars.push_back(var1);

bool is_success = indy.set_tpos_variable(tpos_vars);
if (is_success) {
    std::cout << "TPos 변수가 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "TPos 변수 설정 실패." << std::endl;
}

역기구학 및 시뮬레이션 모드 관련 기능

IndyDCP3 C++ API는 역기구학 수행

, 직접 가르치기 모드 활성화/비활성화, 시뮬레이션 모드 설정 및 로봇을 오류 상태에서 복구하는 기능을 제공합니다.

메서드 설명
inverse_kin(const std::array<float, 6> &tpos, const std::vector<float> &init_jpos, std::vector<float> &jpos) 목표 작업 공간 위치에 도달하기 위한 관절 위치를 계산합니다
set_direct_teaching(bool enable) 직접 가르치기 모드를 활성화 또는 비활성화합니다
set_simulation_mode(bool enable) 시뮬레이션 모드를 활성화 또는 비활성화합니다
recover() 오류 또는 충돌 상태에서 로봇을 복구합니다

inverse_kin() 예제

std::array<float, 6> target_pose = {350.0, -186.5, 522.0, -180.0, 0.0, 180.0};
std::vector<float> init_jpos = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
std::vector<float> calculated_jpos;

bool is_success = indy.inverse_kin(target_pose, init_jpos, calculated_jpos);
if (is_success) {
    std::cout << "역기구학 성공. 관절 위치: ";
    for (float jp : calculated_jpos) {
        std::cout << jp << " ";
    }
    std::cout << std::endl;
} else {
    std::cerr << "역기구학 실패." << std::endl;
}

set_direct_teaching() 예제

bool enable_direct_teaching = true;
bool is_success = indy.set_direct_teaching(enable_direct_teaching);
if (is_success) {
    std::cout << "직접 가르치기 모드가 활성화되었습니다." << std::endl;
} else {
    std::cerr << "직접 가르치기 모드 활성화 실패." << std::endl;
}

set_simulation_mode() 예제

bool enable_simulation = true;
bool is_success = indy.set_simulation_mode(enable_simulation);
if (is_success) {
    std::cout << "시뮬레이션 모드가 활성화되었습니다." << std::endl;
} else {
    std::cerr << "시뮬레이션 모드 활성화 실패." << std::endl;
}

recover() 예제

bool is_success = indy.recover();
if (is_success) {
    std::cout << "복구 성공." << std::endl;
} else {
    std::cerr << "복구 실패." << std::endl;
}

프로그램 제어 함수

프로그램 제어 기능을 사용하면 로봇 프로그램을 시작, 일시 중지, 재개 및 중지할 수 있습니다. 이러한 기능은 미리 작성된 프로그램의 실행 흐름을 관리하는 데 필수적입니다.

메서드 설명
play_program(const std::string &prog_name, int prog_idx) 이름 또는 인덱스로 프로그램을 시작합니다
pause_program() 현재 실행 중인 프로그램을 일시 중지합니다
resume_program() 일시 중지된 프로그램을 다시 시작합니다
stop_program() 현재 실행 중인 프로그램을 중지합니다

play_program() 예제

std::string program_name = "example_program.indy7v2.json";
int program_index = 1;

bool is_success = indy.play_program(program_name, program_index);
if (is_success) {
    std::cout << "프로그램이 성공적으로 시작되었습니다." << std::endl;
} else {
    std::cerr << "프로그램 시작 실패." << std::endl;
}

pause_program() 예제

bool is_success = indy.pause_program();
if (is_success) {
    std::cout << "프로그램이 성공적으로 일시 중지되었습니다." << std::endl;
} else {
    std::cerr << "프로그램 일시 중지 실패." << std::endl;
}

resume_program() 예제

bool is_success = indy.resume_program();
if (is_success) {
    std::cout << "프로그램이 성공적으로 재개되었습니다." << std::endl;
} else {
    std::cerr << "프로그램 재개 실패." << std::endl;
}

stop_program() 예제

bool is_success = indy.stop_program();
if (is_success) {
    std::cout << "프로그램이 성공적으로 중지되었습니다." << std::endl;
} else {
    std::cerr << "프로그램 중지 실패." << std::endl;
}

IndySDK 사용

IndyDCP3 C++ API는 IndySDK를 활성화하고, 사용자 정의 제어 모드를 설정하고, 제어 게인을 관리하는 기능을 제공합니다. 이러한 기능은 사용자 정의 컨트롤러를 개발하려는 고급 사용자에게 중요합니다.

메서드 설명
activate_sdk(const SDKLicenseInfo &request, SDKLicenseResp &response) IndySDK를 활성화합니다
set_custom_control_mode(bool mode) 사용자 정의 제어 모드를 설정합니다
get_custom_control_mode(int &mode) 현재 사용자 정의 제어 모드를 검색합니다
set_custom_control_gain(const CustomGainSet &gain_set) 사용자 컨트롤러에 대한 사용자 정의 제어 게인을 설정합니다
get_custom_control_gain(CustomGainSet &gain_set) 현재 사용자 정의 제어 게인 설정을 검색합니다

activate_sdk() 예제

Nrmk::IndyFramework::SDKLicenseInfo request;
request.set_license_key("YOUR_LICENSE_KEY");
request.set_expire_date("yyyy-mm-dd");

Nrmk::IndyFramework::SDKLicenseResp response;
bool is_success = indy.activate_sdk(request, response);
if (is_success) {
    std::cout << "SDK 활성화됨: " << (response.activated() ? "예" : "아니오") << std::endl;
    std::cout << "응답 코드: " << response.response().code() << ", 메시지: " << response.response().msg() << std::endl;
} else {
    std::cerr << "SDK 활성화 실패." << std::endl;
}

set_custom_control_mode()get_custom_control_mode()** 예제

int mode = 0;
bool is_success = indy.set_custom_control_mode(mode);
if (is_success) {
    std::cout << "사용자 정의 제어 모드가 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "사용자 정의 제어 모드 설정 실패." << std::endl;
}
int get_mode;
bool is_success = indy.get_custom_control_mode(get_mode);
if (is_success) {
    std::cout << "사용자 정의 제어 모드: " << get_mode << std::endl;
} else {
    std::cerr << "사용자 정의 제어 모드 검색 실패." << std::endl;
}

set_custom_control_gain() 예제

Nrmk::IndyFramework::CustomGainSet gain_set;
gain_set.add_gain0(0.0);
gain_set.add_gain0(0.0);
gain_set.add_gain0(0.0);
gain_set.add_gain0(0.0);
gain_set.add_gain0(0.0);
gain_set.add_gain0(0.0);

bool is_success = indy.set_custom_control_gain(gain_set);
if (is_success) {
    std::cout << "사용자 정의 제어 게인이 성공적으로 설정되었습니다." << std::endl;
} else {
    std::cerr << "사용자 정의 제어 게인 설정 실패." << std::endl;
}

get_custom_control_gain() 예제

Nrmk::IndyFramework::CustomGainSet gain_set;
bool is_success = indy.get_custom_control_gain(gain_set);
if (is_success) {
    std::cout << "사용자 정의 제어 게인이 성공적으로 검색되었습니다." << std::endl;
    for (int i = 0; i < gain_set.gain0_size(); ++i) {
        std::cout << "Gain0: " << gain_set.gain0(i) << " ";
    }
    std::cout << std::endl;
} else {
    std::cerr << "사용자 정의 제어 게인 검색 실패." << std::endl;
}

유틸리티 기능

유틸리티 기능은 데이터 로깅 및 시뮬레이션 모드 설정과 같은 추가 기능을 제공합니다.

메서드 설명
start_log() 실시간 데이터 로깅을 시작합니다
end_log() 실시간 데이터 로깅을 종료하고 저장합니다

start_log()end_log()** 예제

bool is_success = indy.start_log();
if (is_success)

 {
    std::cout << "데이터 로깅을 시작했습니다." << std::endl;
}

// 시간이 지난 후...
is_success = indy.end_log();
if (is_success) {
    std::cout << "데이터 로깅이 종료되고 데이터가 저장되었습니다." << std::endl;
}

이 두 함수는 실시간 데이터 로깅에 사용됩니다. start_log()를 호출하면 로봇의 데이터가 메모리에 저장됩니다. 일정 시간이 지난 후 end_log()를 호출하면 메모리 로깅이 중지되고 STEP 내 파일에 작성됩니다. 실시간 데이터 로깅 파일은 다음 경로에서 찾을 수 있습니다:

/home/user/release/IndyDeployments/RTlog/RTLog.csv

더 자세한 사용법 및 고급 기능은 C++ 클라이언트를 참조하세요. Neuromeka Github 저장소.