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': [...],
  'tau_jts': [...],
  'tau_jts_raw1': [...],
  'tau_jts_raw2': [...]
}
  • q, qdot, qddot: 각 관절의 현재 위치(도), 속도(도/초) 및 가속도(도/초²)
  • qdes, qdotdes, qddotdes: 각 관절의 목표 위치(도), 속도(도/초) 및 가속도(도/초²)
  • p, pdot, pddot: 현재 작업 공간 자세 위치(mm), 속도(mm/초) 및 가속도(mm/초²)
  • pdes, pdotdes, pddotdes: 목표 작업 공간 자세 위치(mm), 속도(mm/초) 및 가속도(mm/초²)
  • tau, tau_act, tau_ext: 각 관절의 현재 입력 토크, 실제 토크 및 외부 토크(Nm)
  • tau_jts, tau_jts_raw1, tau_jts_raw2: 각 관절의 관절토크 센서 값

get_servo_data()

Nrmk::IndyFramework::ServoData servo_data;
bool is_success = indy.get_servo_data(servo_data);
if (is_success) {
    std::cout << "servo data:" << std::endl;
    for (int i = 0; i < servo_data.temperatures_size(); i++){
        std::cout << "temperature" << i << ": " << servo_data.temperatures(i) << std::endl;
    }   
}
else{
    std::cout << "Failed to get_servo_data" << std::endl;
}
{
  '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(DigitalList &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 데이터 확인
set_endtool_ao(const AnalogList &data) 엔드툴 AO 데이터 확인 (List)
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;
    }
}

get_do(), 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_STATE);

bool is_success = indy.set_do(do_signal_list);
if (is_success) {
    std::cout << "Set DO successfully." << std::endl;
} else {
    std::cerr << "Failed to set DO." << std::endl;
}

Nrmk::IndyFramework::DigitalList do_data;
is_success = indy.get_do(do_data);
if (is_success) {
    std::cout << "GetDO RPC succeeded." << std::endl;
    for (int i = 0; i < do_data.signals_size(); i++) {
        const auto& signal = do_data.signals(i);
        std::cout << "Address: " << signal.address() << ", State: " << signal.state() << std::endl;
    }
}
else {
    std::cerr << "GetDO RPC failed." << 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;
    }
}

get_ao(), set_ao() 예제

Nrmk::IndyFramework::AnalogList ao_signal_list;
auto* ao_signal1 = ao_signal_list.add_signals();
ao_signal1->set_address(1);
ao_signal1->set_voltage(1000); //mV

auto* ao_signal2 = ao_signal_list.add_signals();
ao_signal2->set_address(2);
ao_signal2->set_voltage(2000); //mV

is_success = indy.set_ao(ao_signal_list);
if (is_success) {
    std::cout << "SetAO RPC succeeded." << std::endl;
} else {
    std::cerr << "SetAO RPC failed." << std::endl;
}

Nrmk::IndyFramework::AnalogList ao_data;
is_success = indy.get_ao(ao_data);
if (is_success) {
    std::cout << "GetAO RPC succeeded." << std::endl;
    for (int i = 0; i < ao_data.signals_size(); ++i) {
        const auto &signal = ao_data.signals(i);
        std::cout << "Address: " << signal.address() << ", Voltage: " << signal.voltage() << std::endl;
    }
} else {
    std::cerr << "GetAO RPC failed." << std::endl;
}

get_endtool_di() 예제

Nrmk::IndyFramework::EndtoolSignalList endtool_di_data;
is_success = indy.get_endtool_di(endtool_di_data);
if (is_success) {
    std::cout << "GetEndDI RPC succeeded." << std::endl;
    for (int i = 0; i < endtool_di_data.signals_size(); i++) {
        const auto& signal = endtool_di_data.signals(i);
        std::cout << "Port: " << signal.port() << std::endl;
        for (const auto& state : signal.states()) {
            std::cout << "State: " << state << std::endl;
        }
    }
} else {
    std::cerr << "GetEndDI RPC failed." << std::endl;
}

get_endtool_do(), set_endtool_do() 예제

Nrmk::IndyFramework::EndtoolSignalList end_do_signal_list;
auto* end_signal1 = end_do_signal_list.add_signals();
end_signal1->set_port("C");
end_signal1->add_states(EndtoolState::UNUSED);

is_success = indy.set_endtool_do(end_do_signal_list);
if (is_success) {
    std::cout << "SetEndDO RPC succeeded." << std::endl;
} else {
    std::cerr << "SetEndDO RPC failed." << std::endl;
}

Nrmk::IndyFramework::EndtoolSignalList endtool_do_data;
is_success = indy.get_endtool_do(endtool_do_data);
if (is_success) {
    std::cout << "GetEndDO RPC succeeded." << std::endl;
    for (int i = 0; i < endtool_do_data.signals_size(); i++) {
        const auto& signal = endtool_do_data.signals(i);
        std::cout << "Port: " << signal.port() << std::endl;
        for (const auto& state : signal.states()) {
            std::cout << "State: " << state << std::endl;
        }
    }
} else {
    std::cerr << "GetEndDO RPC failed." << std::endl;
}

get_endtool_ai() 예제

아날로그 입출력 기능은 RevE 엔드툴에서 사용이 가능하며, 엔드툴 AO 주소는 0과 1 두 가지 채널을 사용할 수 있습니다.

Nrmk::IndyFramework::AnalogList endtool_ai_data;
is_success = indy.get_endtool_ai(endtool_ai_data);
if (is_success) {
    std::cout << "GetEndAI RPC succeeded." << std::endl;
    for (int i = 0; i < endtool_ai_data.signals_size(); i++) {
        const auto& signal = endtool_ai_data.signals(i);
        std::cout << "Address: " << signal.address() << ", Voltage: " << signal.voltage() << std::endl; //mV
    }
} else {
    std::cerr << "GetEndAI RPC failed." << std::endl;
}

get_endtool_ao(), set_endtool_ao() 예제

아날로그 입출력 기능은 RevE 엔드툴에서 사용이 가능하며, 엔드툴 AO 주소는 0과 1 두 가지 채널을 사용할 수 있습니다.

Nrmk::IndyFramework::AnalogList end_ao_signal_list;
auto* end_ao_signal1 = end_ao_signal_list.add_signals();
end_ao_signal1->set_address(1);
end_ao_signal1->set_voltage(1000); //mV

is_success = indy.set_endtool_ao(end_ao_signal_list);
if (is_success) {
    std::cout << "SetEndAO RPC succeeded." << std::endl;
} else {
    std::cerr << "SetEndAO RPC failed." << std::endl;
}

Nrmk::IndyFramework::AnalogList endtool_ao_data;
is_success = indy.get_endtool_ao(endtool_ao_data);
if (is_success) {
    std::cout << "GetEndAO RPC succeeded." << std::endl;
    for (int i = 0; i < endtool_ao_data.signals_size(); i++) {
        const auto& signal = endtool_ao_data.signals(i);
        std::cout << "Address: " << signal.address() << ", Voltage: " << signal.voltage() << std::endl; //mV
    }
} else {
    std::cerr << "GetEndAO RPC failed." << 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) 로봇을 지정된 관절 대상 위치로 이동
movej_time(const std::vector<float> jtarget, const int base_type, const int blending_type, const float blending_radius, const float move_time, 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) 로봇을 지정된 작업공간 위치로 선형 이동
movel_time(const std::array<float, 6> ttarget, const int base_type, const int blending_type, const float blending_radius, const float move_time, 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) 로봇을 원형 경로를 따라 이동
movec_time(const std::array<float, 6>& tpos1, const std::array<float, 6>& tpos2, float angle, int setting_type, int move_type, int base_type, int blending_type, float blending_radius, float move_time, bool const_cond, int cond_type, int react_type, DCPDICond di_condition, DCPVarCond var_condition) 지정된 시간 동안 로봇을 원형 경로를 따라 이동
move_gcode(const std::string& gcode_file, bool is_smooth_mode, float smooth_radius, float vel_ratio, float acc_ratio) 입력된 gcode 파일을 따라 로봇을 이동
add_joint_waypoint(const std::vector<float>& waypoint) get_joint_waypoint(std::vector<std::vector<float>>& waypoints) clear_joint_waypoint() move_joint_waypoint(float move_time) joint waypoints의 집합을 따라 로봇을 이동
add_task_waypoint(const std::array<float, 6>& waypoint) get_task_waypoint(std::vector<std::array<float, 6>>& waypoints) clear_task_waypoint() move_task_waypoint(float move_time) task waypoints의 집합을 따라 로봇을 이동
add_joint_waypoint(const std::vector<float>& waypoint) get_joint_waypoint(std::vector<std::vector<float>>& waypoints) clear_joint_waypoint() move_joint_waypoint(float move_time) 로봇을 일련의 조인트 웨이포인트로 이동
add_task_waypoint(const std::array<float, 6>& waypoint) get_task_waypoint(std::vector<std::array<float, 6>>& waypoints) clear_task_waypoint() move_task_waypoint(float move_time) 로봇을 일련의 작업 경로점으로 이동
move_joint_traj(const std::vector<std::vector<float>>& q_list, const std::vector<std::vector<float>>& qdot_list, const std::vector<std::vector<float>>& qddot_list) 로봇의 제어 주기에 대한 관절공간의 위치-속도-가속도를 한번에 입력받고 입력된 궤적을 따라 로봇을 이동
move_task_traj(const std::vector<std::vector<float>>& p_list, const std::vector<std::vector<float>>& pdot_list, const std::vector<std::vector<float>>& pddot_list) 로봇의 제어 주기에 대한 작업공간의 위치-속도-가속도를 한번에 입력받고 입력된 궤적을 따라 로봇을 이동

주의

모션 명령을 사용할 때는 주의해야 합니다. 명령이 성공적으로 적용되면 로봇이 즉시 움직이기 때문입니다. 펜던트를 통해 로봇을 사용할 때는 사용자가 터치 버튼을 누르고 있는 동안에만 움직일 수 있지만, 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;
}

move_gcode() 예제

G-code 파일을 기반으로 모션을 읽고 실행합니다.

std::string gcode_path = "/path/to/gcode/<gcode file>";
bool is_smooth = false;
float smooth_radius = 0.0f;
float velocity_ratio = 15.0f;
float acceleration_ratio = 100.0f;

bool is_success = indy.move_gcode(
    gcode_path,
    is_smooth,
    smooth_radius,
    velocity_ratio,
    acceleration_ratio
);

if (is_success) {
    std::cout << "G-code motion executed successfully." << std::endl;
} else {
    std::cerr << "Failed to execute G-code motion." << std::endl;
}

관절 경유점, 작업 경유점을 이용한 Move

Joint Waypoints

관절 경유점은 로봇의 각 관절 각도를 나타내며 여러 관절 경유점을 순차적으로 이동하도록 모션을 만들 수 있게 합니다.

add_joint_waypoint(const std::vector<float>& waypoint) 는 관절 경유점을 경유점 리스트에 추가합니다. 경유점은 타겟 관절 위치를 벡터로 표현합니다. waypoint: float으로 표현된 벡터이며 1번부터 6번 까지의 관절 각도를 deg 단위로 나타냅니다.

indy.add_joint_waypoint({0, 0, 0, 0, 0, 0});
indy.add_joint_waypoint({-44, 25, -63, 48, -7, -105});
indy.add_joint_waypoint({0, 0, 90, 0, 90, 0});
indy.add_joint_waypoint({-145, 31, -33, 117, -7, -133});
indy.add_joint_waypoint({-90, -15, -90, 0, -75, 0});

get_joint_waypoint() 현재 경유점 리스트에 저장된 관절 경유점 값을 반환 받을 수 있습니다.

std::vector<std::vector<float>> waypoints;
if (indy.get_joint_waypoint(waypoints)) {
    std::cout << "Successfully retrieved joint waypoints:" << std::endl;
    for (const auto& wp : waypoints) {
        for (float joint : wp) {
            std::cout << joint << " ";
        }
        std::cout << std::endl;
    }
} else {
    std::cerr << "No joint waypoints available." << std::endl;
}

clear_joint_waypoint() 저장된 경유점 리스트를 리셋합니다.

indy.clear_joint_waypoint();

move_joint_waypoint(float move_time) 경유점 리스트에 저장된 관절 경유점을 따라 순차적으로 로봇이 이동합니다. move_time: (옵션) 각 경유점 간의 이동시간을 설정할 수 있습니다.

indy.move_joint_waypoint();
float move_time = 3.0;
indy.move_joint_waypoint(move_time);

Task Waypoints

작업 경유점은 로봇의 작업공간 상의 위치와 자세를 나타내며 여러 작업 경유점을 순차적으로 이동하도록 모션을 만들 수 있게 합니다.

add_task_waypoint(const std::array<float, 6>& waypoint) 는 작업 경유점을 경유점 리스트에 추가합니다. 경유점은 타겟 작업 위치를 벡터로 표현합니다. waypoint: float으로 표현된 벡터이며 x, y, z 위치와 말단의 u, v, w 방향 각도를 나타냅니다.

indy.add_task_waypoint({-186.54f, -454.45f, 415.61f, 179.99f, -0.06f, 89.98f});
indy.add_task_waypoint({-334.67f, -493.07f, 259.00f, 179.96f, -0.12f, 89.97f});
indy.add_task_waypoint({224.79f, -490.20f, 508.08f, 179.96f, -0.14f, 89.97f});
indy.add_task_waypoint({-129.84f, -416.84f, 507.38f, 179.95f, -0.16f, 89.96f});
indy.add_task_waypoint({-186.54f, -454.45f, 415.61f, 179.99f, -0.06f, 89.98f});

get_task_waypoint(std::vector<std::array<float, 6>>& waypoints) 현재 경유점 리스트에 저장된 작업 경유점 값을 반환 받을 수 있습니다.

std::vector<std::array<float, 6>> t_waypoints;
if (indy.get_task_waypoint(t_waypoints)) {
    std::cout << "Successfully retrieved task waypoints:" << std::endl;
    for (const auto& wp : t_waypoints) {
        for (float task : wp) {
            std::cout << task << " ";
        }
        std::cout << std::endl;
    }
} else {
    std::cerr << "No task waypoints available." << std::endl;
}

clear_task_waypoint() 저장된 작업 경유점 리스트를 리셋합니다.

indy.clear_task_waypoint();

move_task_waypoint(float move_time) 경유점 리스트에 저장된 경유점을 따라 순차적으로 로봇이 이동합니다. move_time: (옵션) 각 경유점 간의 이동시간을 설정할 수 있습니다.

indy.move_task_waypoint();
indy.move_task_waypoint(move_time=1.5);

Trajectory Motion

move_joint_traj는 관절 공간 궤적 이동 명령입니다. 아래에서 q_list, qdot_list, qddot_list는 라디안 단위의 관절 위치, 속도 및 가속도의 list 값입니다. 궤적 사이의 시간 간격은 제어 주기이며 기본적으로 250us입니다.

std::vector<std::vector<float>> q_list = {{...}, {...}, ...};
std::vector<std::vector<float>> qdot_list = {{...}, {...}, ...};
std::vector<std::vector<float>> qddot_list = {{...}, {...}, ...};

indy.move_joint_traj(q_list, qdot_list, qddot_list)

move_task_traj는 작업 공간 궤적 이동 명령입니다. 아래에서 p_list, pdot_list, pddot_list는 엔드툴 위치, 속도 및 가속도의 미터 및 라디안 단위의 list 값입니다. 궤적 사이의 시간 단계는 제어 기간이며 기본적으로 250us입니다.

std::vector<std::vector<float>> p_list = {{...}, {...}, ...};
std::vector<std::vector<float>> pdot_list = {{...}, {...}, ...};
std::vector<std::vector<float>> pddot_list = {{...}, {...}, ...};

indy.move_task_traj(p_list, pdot_list, pddot_list)

Waiting Functions

Wait IO: 특정 디지털 또는 아날로그 I/O 신호가 주어진 조건과 일치할 때까지 대기합니다.
Wait Time: 첫 모션 명령이 입력된 후 특정 시간 동안 대기합니다.
Wait Progress: 특정 진행 상태에 도달할 때까지 대기합니다.
Wait Radius: 지정된 반경 내에서 움직임이 완료될 때까지 대기합니다.
Wait Traj: 경로 이동이 완료될 때까지 대기합니다.
- Wait Traj 조건
- TRAJ_STARTED(0): 경로 이동이 막 시작되었음
- TRAJ_ACC_DONE(1): 경로의 가속 구간이 완료되었음
- TRAJ_CRZ_DONE(2): 경로의 순항 구간(일정 속도 구간)이 완료되었음
- TRAJ_DEC_DONE(3): 경로의 감속 구간이 완료되었음

std::vector<float> j_pos_1 = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
indy.movej(j_pos_1, JointBaseType::ABSOLUTE_JOINT, BlendingType_Type::BlendingType_Type_OVERRIDE);

// indy.wait_time(0.1f);
// indy.wait_radius(10);
// indy.wait_traj(TrajCondition::TRAJ_ACC_DONE);
indy.wait_progress(15);

std::vector<float> j_pos_2 = {0.0, 0.0, -90.0, 0.0, -90.0, 0.0};
indy.movej(j_pos_2, JointBaseType::ABSOLUTE_JOINT, BlendingType_Type::BlendingType_Type_OVERRIDE);

wait_io() 사용 예제

특정 디지털 또는 아날로그 I/O 신호가 주어진 조건과 일치할 때까지 대기합니다.

std::vector<Nrmk::IndyFramework::DigitalSignal> di_signals = {
    Nrmk::IndyFramework::DigitalSignal(1, Nrmk::IndyFramework::DigitalState::ON),
    Nrmk::IndyFramework::DigitalSignal(2, Nrmk::IndyFramework::DigitalState::OFF)
};

std::vector<Nrmk::IndyFramework::DigitalSignal> end_di_signals = {
    Nrmk::IndyFramework::DigitalSignal(3, Nrmk::IndyFramework::DigitalState::ON)
};

std::vector<Nrmk::IndyFramework::DigitalSignal> set_do_signals = {
    Nrmk::IndyFramework::DigitalSignal(4, Nrmk::IndyFramework::DigitalState::ON)
};

bool is_success = indy.wait_io(
    di_signals,                           // Digital input signals to wait for
    {},                                   // Digital output signals to wait for
    end_di_signals,                       // Digital input signals to end waiting
    {},                                   // Digital output signals to end waiting
    1,                                    // Conjunction (AND condition)
    set_do_signals,                       // Digital output signals to set during wait
    {},                                   // Digital output signals to set upon end
    {},                                   // Analog output signals to set during wait
    {}                                    // Analog output signals to set upon end
);

if (is_success) {
    std::cout << "WaitIO condition met successfully." << std::endl;
} else {
    std::cerr << "WaitIO condition failed." << std::endl;
}

텔레오퍼레이션 관련 함수

텔레오퍼레이션 관련 함수는 사용자가 로봇을 원격 제어할 수 있도록 하는 기능을 제공합니다. 이 함수들을 통해 로봇의 모션을 실시간으로 조정하고, 다양한 조작 모드에서 로봇을 제어할 수 있습니다. start_teleop 함수를 사용하여 텔레오퍼레이션 모드를 시작하고, stop_teleop 함수로 모드를 종료할 수 있습니다. 또한, movetelej_abs/movetelej_relmovetelel_abs/movetelel_rel 함수를 사용하여 각각 관절 공간과 작업 공간에서의 로봇 움직임을 업데이트할 수 있습니다.

Note

텔레오퍼레이션 모션 이용 시 IndyDCP3를 통해 실시간으로 지속적 목표 위치를 업데이트하게 되면 로봇은 이를 스트리밍하여 즉각적이면서 스무스한 모션을 생성합니다. 기존 Motion 명령들 (movej, movel)은 목표 위치로의 경로 생성을 부드럽게 수행하지만 원격제어와 같은 즉각적인 반응을 할 수는 없습니다. 이 점이 텔레오퍼레이션 모션의 특징입니다.

Function Description
start_teleop(TeleMethod method) 텔레오퍼레이션 모드 시작
stop_teleop() 현재 실행 중인 텔레오퍼레이션 모드 종료
get_teleop_device(Nrmk::IndyFramework::TeleOpDevice& device) 현재 연결된 텔레오퍼레이션 장치에 대한 정보를 가져옵니다.
get_teleop_state(Nrmk::IndyFramework::TeleOpState& state) 현재 텔레오퍼레이션 상태를 가져옵니다.
connect_teleop_device(const std::string& name, Nrmk::IndyFramework::TeleOpDevice_TeleOpDeviceType type, const std::string& ip, uint32_t port) 지정된 매개변수로 텔레오퍼레이션 장치에 연결합니다.
disconnect_teleop_device() 현재 연결된 텔레오퍼레이션 장치의 연결을 해제합니다.
read_teleop_input(Nrmk::IndyFramework::TeleP& teleop_input) 텔레오퍼레이션 장치에서 현재 입력 값을 읽어옵니다.
set_play_rate(const float rate) 텔레오퍼레이션 모션 재생 속도를 설정합니다.
get_play_rate(float& rate) 텔레오퍼레이션 모션 재생의 현재 재생 속도를 가져옵니다.
get_tele_file_list(std::vector<std::string>& files) 저장된 텔레오퍼레이션 모션 파일 목록을 가져옵니다.
save_tele_motion(const std::string& name) 현재 텔레오퍼레이션 모션을 지정된 이름으로 저장합니다.
load_tele_motion(const std::string& name) 저장된 텔레오퍼레이션 모션을 이름으로 불러옵니다.
delete_tele_motion(const std::string& name) 저장된 텔레오퍼레이션 모션을 이름으로 삭제합니다.
enable_tele_key(const bool enable) 텔레오퍼레이션 키 입력을 활성화하거나 비활성화합니다.

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;
}

get_teleop_device() 예제

현재 연결된 텔레오퍼레이션 장치에 대한 정보를 가져옵니다.

Nrmk::IndyFramework::TeleOpDevice device;

bool is_success = indy.get_teleop_device(device);

if (is_success) {
    std::cout << "Teleoperation device name: " << device.name() << std::endl;
    std::cout << "Device IP: " << device.ip() << std::endl;
} else {
    std::cerr << "Failed to retrieve teleoperation device information." << std::endl;
}

get_teleop_state() 예제

현재 텔레오퍼레이션 상태를 가져옵니다.

Nrmk::IndyFramework::TeleOpState state;

bool is_success = indy.get_teleop_state(state);

if (is_success) {
    std::cout << "Teleoperation state: " << state.state() << std::endl;
} else {
    std::cerr << "Failed to retrieve teleoperation state." << std::endl;
}

connect_teleop_device() 예제

지정된 매개변수로 텔레오퍼레이션 장치에 연결합니다.

std::string device_name = "TeleOpDevice1";
Nrmk::IndyFramework::TeleOpDevice_TeleOpDeviceType type = Nrmk::IndyFramework::TeleOpDevice_TeleOpDeviceType::TeleOpDeviceType_JOYSTICK;
std::string ip = "192.168.0.2";
uint32_t port = 5555;

bool is_success = indy.connect_teleop_device(device_name, type, ip, port);

if (is_success) {
    std::cout << "Teleoperation device connected successfully." << std::endl;
} else {
    std::cerr << "Failed to connect to teleoperation device." << std::endl;
}

disconnect_teleop_device() 예제

현재 연결된 텔레오퍼레이션 장치의 연결을 해제합니다.

bool is_success = indy.disconnect_teleop_device();

if (is_success) {
    std::cout << "Teleoperation device disconnected successfully." << std::endl;
} else {
    std::cerr << "Failed to disconnect teleoperation device." << std::endl;
}

read_teleop_input() 예제

텔레오퍼레이션 장치에서 현재 입력 값을 읽어옵니다.

Nrmk::IndyFramework::TeleP teleop_input;

bool is_success = indy.read_teleop_input(teleop_input);

if (is_success) {
    std::cout << "Teleoperation input read successfully." << std::endl;
    // Process teleop_input as needed
} else {
    std::cerr << "Failed to read teleoperation input." << std::endl;
}

set_play_rate() 예제

텔레오퍼레이션 모션 재생 속도를 설정합니다.

float playback_rate = 1.2;

bool is_success = indy.set_play_rate(playback_rate);

if (is_success) {
    std::cout << "Playback rate set successfully to " << playback_rate << std::endl;
} else {
    std::cerr << "Failed to set playback rate." << std::endl;
}

get_play_rate() 예제

텔레오퍼레이션 모션 재생의 현재 재생 속도를 가져옵니다.

float playback_rate;

bool is_success = indy.get_play_rate(playback_rate);

if (is_success) {
    std::cout << "Current playback rate: " << playback_rate << std::endl;
} else {
    std::cerr << "Failed to retrieve playback rate." << std::endl;
}

get_tele_file_list() 예제

텔레오퍼레이션 모션 파일 목록을 가져옵니다.

std::vector<std::string> files;

bool is_success = indy.get_tele_file_list(files);

if (is_success) {
    std::cout << "Retrieved teleoperation files:" << std::endl;
    for (const auto& file : files) {
        std::cout << " - " << file << std::endl;
    }
} else {
    std::cerr << "Failed to retrieve teleoperation file list." << std::endl;
}

save_tele_motion() 예제

텔레오퍼레이션 모션을 지정된 이름으로 저장합니다.

std::string motion_name = "MyTeleMotion";

bool is_success = indy.save_tele_motion(motion_name);

if (is_success) {
    std::cout << "Teleoperation motion saved successfully as " << motion_name << std::endl;
} else {
    std::cerr << "Failed to save teleoperation motion." << std::endl;
}

load_tele_motion() 예제

텔레오퍼레이션 모션을 이름으로 불러옵니다.

std::string motion_name = "MyTeleMotion";

bool is_success = indy.load_tele_motion(motion_name);

if (is_success) {
    std::cout << "Teleoperation motion " << motion_name << " loaded successfully." << std::endl;
} else {
    std::cerr << "Failed to load teleoperation motion." << std::endl;
}

delete_tele_motion() 예제

텔레오퍼레이션 모션을 이름으로 삭제합니다.

std::string motion_name = "MyTeleMotion";

bool is_success = indy.delete_tele_motion(motion_name);

if (is_success) {
    std::cout << "Teleoperation motion " << motion_name << " deleted successfully." << std::endl;
} else {
    std::cerr << "Failed to delete teleoperation motion." << std::endl;
}

enable_tele_key() 예제

텔레오퍼레이션 키 입력을 활성화하거나 비활성화합니다.

bool enable_key = true;

bool is_success = indy.enable_tele_key(enable_key);

if (is_success) {
    std::cout << "Teleoperation key input enabled." << std::endl;
} else {
    std::cerr << "Failed to enable teleoperation key input." << 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) 현재 사용자 정의 제어 게인 설정을 검색합니다
set_joint_control_gain(const std::vector<float>& kp, const std::vector<float>& kv, const std::vector<float>& kl2) Joint-Level 컨트롤러의 제어게인 설정
get_joint_control_gain(std::vector<float>& kp, std::vector<float>& kv, std::vector<float>& kl2) Joint-Level 컨트롤러의 제어게인 확인
set_task_control_gain(const std::vector<float>& kp, const std::vector<float>& kv, const std::vector<float>& kl2) Task-Level 컨트롤러의 제어게인 설정
get_task_control_gain(std::vector<float>& kp, std::vector<float>& kv, std::vector<float>& kl2) Task-Level 컨트롤러의 제어게인 확인
set_impedance_control_gain(const std::vector<float>& mass, const std::vector<float>& damping, const std::vector<float>& stiffness, const std::vector<float>& kl2) 임피던스 제어게인 설정
get_impedance_control_gain(std::vector<float>& mass, std::vector<float>& damping, std::vector<float>& stiffness, std::vector<float>& kl2) 현재 임피던스 제어게인 확인
set_force_control_gain(const std::vector<float>& kp, const std::vector<float>& kv, const std::vector<float>& kl2, const std::vector<float>& mass, const std::vector<float>& damping, const std::vector<float>& stiffness, const std::vector<float>& kpf, const std::vector<float>& kif) 힘 제어게인 설정
get_force_control_gain(std::vector<float>& kp, std::vector<float>& kv, std::vector<float>& kl2, std::vector<float>& mass, std::vector<float>& damping, std::vector<float>& stiffness, std::vector<float>& kpf, std::vector<float>& kif) 현재 힘 제어게인 확인

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;
}

set_joint_control_gain() 예제

std::vector<float> kp = {...};
std::vector<float> kv = {...};
std::vector<float> kl2 = {...};

bool is_success = indy.set_joint_control_gain(kp, kv, kl2);

if (is_success) {
    std::cout << "Joint control gains set successfully." << std::endl;
} else {
    std::cerr << "Failed to set joint control gains." << std::endl;
}

get_joint_control_gain() 예제

std::vector<float> kp, kv, kl2;

bool is_success = indy.get_joint_control_gain(kp, kv, kl2);

if (is_success) {
    std::cout << "Joint control gains retrieved successfully." << std::endl;
    std::cout << "KP: ";
    for (const auto& value : kp) std::cout << value << " ";
    std::cout << "\nKV: ";
    for (const auto& value : kv) std::cout << value << " ";
    std::cout << "\nKL2: ";
    for (const auto& value : kl2) std::cout << value << " ";
    std::cout << std::endl;
} else {
    std::cerr << "Failed to retrieve joint control gains." << std::endl;
}

set_task_control_gain() 예제

std::vector<float> kp = {...};
std::vector<float> kv = {...};
std::vector<float> kl2 = {...};

bool is_success = indy.set_task_control_gain(kp, kv, kl2);

if (is_success) {
    std::cout << "Task control gains set successfully." << std::endl;
} else {
    std::cerr << "Failed to set task control gains." << std::endl;
}

get_task_control_gain() 예제

std::vector<float> kp, kv, kl2;

bool is_success = indy.get_task_control_gain(kp, kv, kl2);

if (is_success) {
    std::cout << "Task control gains retrieved successfully." << std::endl;
    std::cout << "KP: ";
    for (const auto& value : kp) std::cout << value << " ";
    std::cout << "\nKV: ";
    for (const auto& value : kv) std::cout << value << " ";
    std::cout << "\nKL2: ";
    for (const auto& value : kl2) std::cout << value << " ";
    std::cout << std::endl;
} else {
    std::cerr << "Failed to retrieve task control gains." << std::endl;
}

set_impedance_control_gain() 예제

std::vector<float> mass = {...};
std::vector<float> damping = {...};
std::vector<float> stiffness = {...};
std::vector<float> kl2 = {...};

bool is_success = indy.set_impedance_control_gain(mass, damping, stiffness, kl2);

if (is_success) {
    std::cout << "Impedance control gains set successfully." << std::endl;
} else {
    std::cerr << "Failed to set impedance control gains." << std::endl;
}

get_impedance_control_gain() 예제

std::vector<float> mass, damping, stiffness, kl2;

bool is_success = indy.get_impedance_control_gain(mass, damping, stiffness, kl2);

if (is_success) {
    std::cout << "Impedance control gains retrieved successfully." << std::endl;
    std::cout << "Mass: ";
    for (const auto& value : mass) std::cout << value << " ";
    std::cout << "\nDamping: ";
    for (const auto& value : damping) std::cout << value << " ";
    std::cout << "\nStiffness: ";
    for (const auto& value : stiffness) std::cout << value << " ";
    std::cout << "\nKL2: ";
    for (const auto& value : kl2) std::cout << value << " ";
    std::cout << std::endl;
} else {
    std::cerr << "Failed to retrieve impedance control gains." << std::endl;
}

set_force_control_gain() 예제

std::vector<float> kp = {...};
std::vector<float> kv = {...};
std::vector<float> kl2 = {...};
std::vector<float> mass = {...};
std::vector<float> damping = {...};
std::vector<float> stiffness = {...};
std::vector<float> kpf = {...};
std::vector<float> kif = {...};

bool is_success = indy.set_force_control_gain(kp, kv, kl2, mass, damping, stiffness, kpf, kif);

if (is_success) {
    std::cout << "Force control gains set successfully." << std::endl;
} else {
    std::cerr << "Failed to set force control gains." << std::endl;
}

get_force_control_gain() 예제

std::vector<float> kp, kv, kl2, mass, damping, stiffness, kpf, kif;
bool is_success = indy.get_force_control_gain(kp, kv, kl2, mass, damping, stiffness, kpf, kif);

if (is_success) {
    std::cout << "Force control gains retrieved successfully." << std::endl;
    std::cout << "KP: ";
    for (const auto& value : kp) std::cout << value << " ";
    std::cout << "\nKV: ";
    for (const auto& value : kv) std::cout << value << " ";
    std::cout << "\nKL2: ";
    for (const auto& value : kl2) std::cout << value << " ";
    std::cout << "\nMass: ";
    for (const auto& value : mass) std::cout << value << " ";
    std::cout << "\nDamping: ";
    for (const auto& value : damping) std::cout << value << " ";
    std::cout << "\nStiffness: ";
    for (const auto& value : stiffness) std::cout << value << " ";
    std::cout << "\nKPF: ";
    for (const auto& value : kpf) std::cout << value << " ";
    std::cout << "\nKIF: ";
    for (const auto& value : kif) std::cout << value << " ";
    std::cout << std::endl;
} else {
    std::cerr << "Failed to retrieve force control gains." << std::endl;
}

유틸리티 기능

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

메서드 설명
start_log() 실시간 데이터 로깅 시작
end_log() 실시간 데이터 로깅을 종료하고 파일로 저장
wait_for_operation_state(op_state) 로봇이 특정 운영 상태에 도달할 때까지 대기
wait_for_motion_state(motion_state) 로봇이 특정 모션 상태에 도달할 때까지 대기
set_friction_comp_state(const bool enable) 마찰 보상 활성화 / 비활성화
get_friction_comp_state() 마찰 보상의 현재 상태 불러오기
set_mount_pos(float rot_y, float rot_z) Y와 Z방향 회전으로 로봇 베이스의 마운팅 각도 설정
get_mount_pos(float &rot_y, float &rot_z) 로봇 베이스의 현재 마운팅 각도 불러오기
set_brakes(const std::vector<bool>& brake_state_list) 각 모터의 브레이크 상태 설정
set_servo_all(const bool enable) 모든 서보 활성화 / 비활성화
set_servo(const uint32_t index, const bool enable) 특정 인덱스의 서보 활설화 / 비활성화
set_endtool_led_dim(const uint32_t led_dim) 엔드 이펙터의 LED 밝기 설정
execute_tool(const std::string& name) 입력된 이름의 툴 함수 실행
get_el5001(int& status, int& value, int& delta, float& average) EL5001 장치로부터 데이터 불러오기
get_el5101(int& status, int& value, int& latch, int& delta, float& average) EL5101 장치로부터 데이터 불러오기
get_brake_control_style(int& style) 현재 브레이크 제어 방법 불러오기
set_conveyor_name(const std::string& name) 컨베이어의 이름 설정
set_conveyor_encoder(int encoder_type, int64_t channel1, int64_t channel2, int64_t sample_num, float mm_per_tick, float vel_const_mmps, bool reversed) 컨베이어 엔코더의 환경설정
set_conveyor_trigger(int trigger_type, int64_t channel, bool detect_rise) 컨베이어 트리거 설정
set_conveyor_offset(float offset_mm) 컨베이어 작업의 offset 값 설정 (밀리미터 단위)
set_conveyor_starting_pose(const std::vector<float>& jpos, const std::vector<float>& tpos) 컨베이어 작업의 시작 joint 및 task 위치 설정
set_conveyor_terminal_pose(const std::vector<float>& jpos, const std::vector<float>& tpos) 컨베이어 작업의 마지막 joint 및 task 위치 설정

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 저장소.

wait_for_operation_state(op_state)

예를 들어, 로봇이 MOVING 상태에 도달할 때까지 기다리고 싶다면, 다음과 같이 호출할 수 있습니다.

bool is_success = indy.wait_for_operation_state(OpState::OP_MOVING);
if (is_success) {
    std::cout << "로봇이 목표 위치에 도달했습니다." << std::endl;
} else {
    std::cerr << "로봇이 목표 위치에 도달하는 데 실패했습니다." << std::endl;
}

wait_for_motion_state(motion_state)

  • motion_state:
    • is_target_reached (목표 도달 여부)
    • is_in_motion (모션 진행 중)
    • is_pausing (일시 중지 상태)
    • is_stopping (정지 상태)
    • has_motion (모션 발생 여부)

예를 들어, 로봇의 모션이 완료될 때까지 기다리고 싶다면, 'is_target_reached' 상태를 사용하여 다음과 같이 호출할 수 있습니다.

bool is_success = indy.wait_for_motion_state("is_target_reached");
if (is_success) {
    std::cout << "로봇이 목표 위치에 도달했습니다." << std::endl;
} else {
    std::cerr << "로봇이 목표 위치에 도달하는 데 실패했습니다." << std::endl;
}

set_friction_comp_state() 예제

bool is_success = indy.set_friction_comp_state(true);

if (is_success) {
    std::cout << "Friction compensation enabled successfully." << std::endl;
} else {
    std::cerr << "Failed to enable friction compensation." << std::endl;
}

get_friction_comp_state() 예제

bool is_enabled = indy.get_friction_comp_state();

if (is_enabled) {
    std::cout << "Friction compensation is currently enabled." << std::endl;
} else {
    std::cout << "Friction compensation is currently disabled." << std::endl;
}

set_mount_pos(float rot_y, float rot_z) 예제

Y와 Z방향 회전으로 로봇 베이스의 마운팅 각도를 설정합니다.

float rotation_y = 10.0f; // Rotation around Y-axis in degrees
float rotation_z = 5.0f;  // Rotation around Z-axis in degrees

bool is_success = indy.set_mount_pos(rotation_y, rotation_z);

if (is_success) {
    std::cout << "Mounting angles set successfully." << std::endl;
} else {
    std::cerr << "Failed to set mounting angles." << std::endl;
}

get_mount_pos(float &rot_y, float &rot_z) 예제

로봇 베이스의 현재 마운팅 각도를 불러옵니다.

float rotation_y, rotation_z;
bool is_success = indy.get_mount_pos(rotation_y, rotation_z);

if (is_success) {
    std::cout << "Retrieved mounting angles:" << std::endl;
    std::cout << "Rotation Y: " << rotation_y << " degrees" << std::endl;
    std::cout << "Rotation Z: " << rotation_z << " degrees" << std::endl;
} else {
    std::cerr << "Failed to retrieve mounting angles." << std::endl;
}

set_brakes(const std::vector<bool>& brake_state_list) 예제

각 모터의 브레이크 상태를 설정합니다.

std::vector<bool> brake_states = {true, false, true, true, false, false};

bool is_success = indy.set_brakes(brake_states);

if (is_success) {
    std::cout << "Brakes set successfully." << std::endl;
} else {
    std::cerr << "Failed to set brakes." << std::endl;
}

set_servo_all(const bool enable) 예제

bool enable_servos = true;
bool is_success = indy.set_servo_all(enable_servos);

if (is_success) {
    std::cout << "All servos enabled successfully." << std::endl;
} else {
    std::cerr << "Failed to enable all servos." << std::endl;
}

set_servo(const uint32_t index, const bool enable) 예제

특정 인덱스의 서보를 활설화 또는 비활성화합니다.

uint32_t servo_index = 3;
bool enable_servo = true;

bool is_success = indy.set_servo(servo_index, enable_servo);

if (is_success) {
    std::cout << "Servo " << servo_index << " enabled successfully." << std::endl;
} else {
    std::cerr << "Failed to enable servo " << servo_index << "." << std::endl;
}

set_endtool_led_dim(const uint32_t led_dim) 예제

엔드 이펙터 LED의 밝기를 설정합니다.

uint32_t led_brightness = ...;

bool is_success = indy.set_endtool_led_dim(led_brightness);

if (is_success) {
    std::cout << "End-effector LED brightness set to " << led_brightness << "." << std::endl;
} else {
    std::cerr << "Failed to set LED brightness." << std::endl;
}

execute_tool(const std::string& name) 예제

std::string tool_name = "GripperOpen";
bool is_success = indy.execute_tool(tool_name);

if (is_success) {
    std::cout << "Tool function '" << tool_name << "' executed successfully." << std::endl;
} else {
    std::cerr << "Failed to execute tool function '" << tool_name << "'." << std::endl;
}

get_el5001(int& status, int& value, int& delta, float& average) 예제

EL5001 장치로부터 데이터를 불러옵니다.

int status, value, delta;
float average;

bool is_success = indy.get_el5001(status, value, delta, average);

if (is_success) {
    std::cout << "EL5001 Data:" << std::endl;
    std::cout << "Status: " << status << ", Value: " << value << ", Delta: " << delta << ", Average: " << average << std::endl;
} else {
    std::cerr << "Failed to retrieve data from EL5001 device." << std::endl;
}

get_el5101(int& status, int& value, int& latch, int& delta, float& average) 예제

EL5101 장치로부터 데이터를 불러옵니다.

int status, value, latch, delta;
float average;

bool is_success = indy.get_el5101(status, value, latch, delta, average);

if (is_success) {
    std::cout << "EL5101 Data:" << std::endl;
    std::cout << "Status: " << status << ", Value: " << value << ", Latch: " << latch << ", Delta: " << delta << ", Average: " << average << std::endl;
} else {
    std::cerr << "Failed to retrieve data from EL5101 device." << std::endl;
}

get_brake_control_style(int& style) 예제

현재 브레이크의 제어 방법을 불러옵니다.

int style;

bool is_success = indy.get_brake_control_style(style);

if (is_success) {
    std::cout << "Brake control style: " << style << std::endl;
} else {
    std::cerr << "Failed to retrieve brake control style." << std::endl;
}

set_conveyor_name(const std::string& name) 예제

컨베이어의 이름을 설정합니다.

std::string conveyor_name = "MainConveyor";

bool is_success = indy.set_conveyor_name(conveyor_name);

if (is_success) {
    std::cout << "Conveyor name set to '" << conveyor_name << "'." << std::endl;
} else {
    std::cerr << "Failed to set conveyor name." << std::endl;
}

set_conveyor_encoder(...) 예제

int encoder_type = 1; // Type of encoder
int64_t channel1 = 0, channel2 = 1, sample_num = 100;
float mm_per_tick = 0.01, vel_const_mmps = 500.0;
bool reversed = false;

bool is_success = indy.set_conveyor_encoder(encoder_type, channel1, channel2, sample_num, mm_per_tick, vel_const_mmps, reversed);

if (is_success) {
    std::cout << "Conveyor encoder configured successfully." << std::endl;
} else {
    std::cerr << "Failed to configure conveyor encoder." << std::endl;
}

set_conveyor_trigger(int trigger_type, int64_t channel, bool detect_rise) 예제

int trigger_type = 2; // Trigger type
int64_t channel = 0;
bool detect_rise = true;

bool is_success = indy.set_conveyor_trigger(trigger_type, channel, detect_rise);

if (is_success) {
    std::cout << "Conveyor trigger set successfully." << std::endl;
} else {
    std::cerr << "Failed to set conveyor trigger." << std::endl;
}

set_conveyor_offset(float offset_mm) 예제

컨베이어 작업에 대해 밀리미터 단위의 offset 값을 설정합니다.

float offset = ...;

bool is_success = indy.set_conveyor_offset(offset);

if (is_success) {
    std::cout << "Conveyor offset set to " << offset << " mm." << std::endl;
} else {
    std::cerr << "Failed to set conveyor offset." << std::endl;
}

set_conveyor_starting_pose(const std::vector<float>& jpos, const std::vector<float>& tpos) 예제

컨베이어 작업의 시작 joint 및 task 위치 설정합니다.

std::vector<float> joint_positions = {0.0, 0.0, 0.0, 0.0, 0.0, 0.0};
std::vector<float> task_positions = {};

bool is_success = indy.set_conveyor_starting_pose(joint_positions, task_positions);

if (is_success) {
    std::cout << "Conveyor starting pose set successfully." << std::endl;
} else {
    std::cerr << "Failed to set conveyor starting pose." << std::endl;
}

set_conveyor_terminal_pose(const std::vector<float>& jpos, const std::vector<float>& tpos) 예제

컨베이어 작업의 마지막 joint 및 task 위치 설정합니다.

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

bool is_success = indy.set_conveyor_terminal_pose(joint_positions, task_positions);

if (is_success) {
    std::cout << "Conveyor terminal pose set successfully." << std::endl;
} else {
    std::cerr << "Failed to set conveyor terminal pose." << std::endl;
}