Skip to content

C++ IndyDCP3 Client

To use the IndyDCP3 client with C++, follow the steps below. This guide assumes that you have the appropriate development environment set up with C++17 or later.

Installation Requirements

  • Requires CMake for project configuration and building.
  • A C++ compiler that supports C++17 or later.
  • IndyDCP3 library files and headers.

Installation Instructions

On Linux

1. Install gRPC

This gRPC installation guide for Linux is summarized from gRPC website. For more information, please visit grpc.io.

Choose a directory to hold locally installed packages. This page assumes that the environment variable MY_INSTALL_DIR holds this directory path. For example:

export MY_INSTALL_DIR=$HOME/.local
Ensure that the directory exists:
mkdir -p $MY_INSTALL_DIR

Add the local bin folder to your path variable, for example:

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

Install CMake You need version 3.13 or later of cmake. Install it by following these instructions:

sudo apt install -y cmake
Check the version of cmake:
cmake --version

On Linux, the system-wide CMake version might be outdated. To install a more recent version in your local installation directory, use:

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

Install other required tools Install the basic tools required to build gRPC:

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

Clone the grpc repo and its submodules:

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

Build and Install gRPC and Protocol Buffers

gRPC applications often use Protocol Buffers for service definitions and data serialization, as in the example code that follows. To build and locally install gRPC and Protocol Buffers, run:

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

Important

Note

It is strongly recommended to install gRPC locally with a properly set CMAKE_INSTALL_PREFIX, as there is no simple way to uninstall gRPC after a global installation.

2. Download and Build example

Clone the Example Repository

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

Navigate to the C++ Folder

cd neuromeka-package/cpp/

Create and Enter the Build Directory

mkdir build && cd build

Run CMake Configuration and Build the Example

cmake -DBUILD_PROTO=OFF ..
cmake --build .
If you need to rebuild the .proto files, set -DBUILD_PROTO=ON. The build_proto executable file will be generated. After running this file, the generated proto files will be located in the proto/cpp_generated folder.

C++ (On Windows)

It is recommended to use Visual Studio Code for this setup.

1. Setup your environment

Install Visual Studio Code - Install following extensions: C/C++, C/C++ Extension Pack and CMake Tools.

Install vs_BuildTools - In BuildTools option, please choose Desktop Development with C++ and Visual Studio extension development.

2. Install GRPC

When you are all set, please open Developer Command Prompt and run the following commands:

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

Create build folder

cd cmake
mkdir build
cd build

Configure and build using 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 ../..
You can set you install path with "-DCMAKE_INSTALL_PREFIX=\<your path>

Build and install grpc

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

3. Download and Build example

Clone the Example Repository

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

Open Visual Studio Code and open neuromeka-package/cpp/ folder Config your build with settings.json in .vscode folder. If you need to rebuild the .proto files, set -DBUILD_PROTO=ON. The build_proto executable file will be generated.

Then, modify the CMakeList.txt. Change following lines to point to your grpc installation directory.

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")

Open Visual Studio Code Press Ctrl+Shift+P or go to View -> Command Palette to open the Command Palette, and choose the following commands: - CMake: Scan for kits: To scan for compilers on your computer. - CMake: Select a kit: To select a specific compiler (e.g., Visual Studio Build Tools 2022 Release - amd64).

When you are done, press the Build button at the bottom left.


Using IndyDCP3

To create a client object, include the IndyDCP3 class header from the IndyDCP3 library and initialize it with the robot's IP address.

#include "indydcp3.h"

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

    // Use the indy object to interact with the robot...
    return 0;
}
  • 192.168.xxx.xxx: IP address of the robot controller.

Methods and Functions

Below is a list of protocol functions that can be called using the IndyDCP3 object. Please refer to the usage methods and input/output examples for each function.

Real-Time Data Acquisition Functions

You can retrieve the robot's current motion status, control data, state, servo motor state, error information, and program status.

Method Description
get_robot_data() Robot status data
get_control_state() Control state
get_motion_data() Motion data
get_servo_data() Servo data
get_violation_data() Error data
get_program_data() Robot program data

get_robot_data()

Nrmk::IndyFramework::ControlData control_data;
bool is_success = indy.get_robot_data(control_data);
if (is_success) {
    // Process 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: Robot operating hours
  • running_mins: Robot operating minutes
  • running_secs: Robot operating seconds
  • op_state: Robot state as defined in the OpState class
    • 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) {
    // Access joint positions
    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: Current positions (deg), velocities (deg/s), and accelerations (deg/s²) of each joint
  • qdes, qdotdes, qddotdes: Target positions (deg), velocities (deg/s), and accelerations (deg/s²) of each joint
  • p, pdot, pddot: Current workspace pose positions (mm), velocities (mm/s), and accelerations (mm/s²)
  • pdes, pdotdes, pddotdes: Target workspace pose positions (mm), velocities (mm/s), and accelerations (mm/s²)
  • tau, tau_act, tau_ext: Current input torques, actual torques, and external torques (Nm) for each joint

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: Status codes (CiA402) for each joint servo
  • temperatures: Temperatures for each joint servo
  • voltages: Voltages for each joint servo
  • currents: Currents for each joint servo
  • servo_actives: Activation state of each joint servo (true/false)
  • brake_actives: Activation state of the brakes for each joint servo (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: Index of the joint where the violation occurred
  • i_args: Integer information about the violation
  • f_args: Float information about the violation
  • violation_str: Error message

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: Name of the currently running program file
  • program_state: Program execution state
    • ProgramState: IDLE (0), RUNNING (1), PAUSING (2), STOPPING (3)

I/O Device functions are used to interact with various robot hardware components like digital and analog I/O, end-tool I/O, and sensors.

Method Description
get_di(DigitalList &data) Retrieves IO board DI data
get_do(DigitalList &data) Retrieves IO board DO data
set_do(const DigitalList &data) Sets IO board DO data
get_ai(AnalogList &data) Retrieves IO board AI data
get_ao(AnalogList &data) Retrieves IO board AO data
set_ao(const AnalogList &data) Sets IO board AO data
get_endtool_di(EndtoolSignalList &data) Retrieves end-tool DI data
get_endtool_do(EndtoolSignalList &data) Retrieves end-tool DO data
set_endtool_do(const EndtoolSignalList &data) Sets end-tool DO data
get_endtool_ai(AnalogList &data) Retrieves end-tool AI data
get_endtool_ao(AnalogList &data) Retrieves end-tool AO data
get_device_info(DeviceInfo &data) Retrieves device information
get_ft_sensor_data(FTSensorData &data) Retrieves end-tool F/T sensor data

get_di() Example

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 << " Address: " << di_data.signals(i).address()
                  << ", State: " << di_data.signals(i).state() << std::endl;
    }
}

set_do() Example

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 << "Set DO successfully." << std::endl;
} else {
    std::cerr << "Failed to set DO." << std::endl;
}

get_ai() Example

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 << " Address: " << ai_data.signals(i).address()
                  << ", Voltage: " << ai_data.signals(i).voltage() << std::endl;
    }
}

Motion Command Functions

Motion command functions allow you to control the robot's movement, whether it's stopping, moving to specific positions, or executing complex motion paths.

Method Description
stop_motion(StopCategory stop_category) Stops motion according to the specified stop category
move_home() Moves the robot to the home position
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) Moves the robot to a specified joint target position
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) Moves the robot to a specified linear target position
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) Moves the robot along a circular path
start_teleop(TeleMethod method) Starts teleoperation mode
stop_teleop() Ends teleoperation mode

Warning

Be cautious when using motion commands, as the robot will move immediately if the command is successfully applied. While using the robot through the pendant allows movement only while the user is holding the touch button, using the API allows movement through program commands, so always ensure the area is clear of objects that could cause collisions. Especially, be mindful of safety if setting high speeds or accelerations, as the robot may move faster than expected.

stop_motion() Example

This function stops the robot's motion according to the specified stop category.

StopCategory stop_category = StopCategory::SMOOTH_BRAKE;
bool is_success = indy.stop_motion(stop_category);
if (is_success) {
    std::cout << "Motion stopped successfully." << std::endl;
} else {
    std::cerr << "Failed to stop motion." << std::endl;
}

move_home() Example

This function moves the robot to the predefined home position.

bool is_success = indy.move_home();
if (is_success) {
    std::cout << "Robot moved to home position successfully." << std::endl;
} else {
    std::cerr << "Failed to move robot to home position." << std::endl;
}

movej() Example

This function moves the robot to a specified joint target position.

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 command executed successfully." << std::endl;
} else {
    std::cerr << "MoveJ command failed." << std::endl;
}

movel() Example

This function moves the robot to a specified linear target position in the workspace.

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 command executed successfully." << std::endl;
} else {
    std::cerr << "MoveL command failed." << std::endl;
}

movec() Example

This function moves the robot along a circular path passing through two specified workspace positions.

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 << "Circular move executed successfully." << std::endl;
} else {
    std::cerr << "Failed to execute circular move." << std::endl;
}

start_teleop() Example

This function starts teleoperation mode with the specified method.

TeleMethod method = TeleMethod::TELE_JOINT_RELATIVE;
bool is_success = indy.start_teleop(method);
if (is_success) {
    std::cout << "Teleoperation mode started successfully." << std::endl;
} else {
    std::cerr << "Failed to start teleoperation mode." << std::endl;
}

stop_teleop() Example

This function stops the teleoperation mode.

bool is_success = indy.stop_teleop();
if (is_success) {
    std::cout << "Teleoperation mode stopped successfully." << std::endl;
} else {
    std::cerr << "Failed to stop teleoperation mode." << std::endl;
}

Variable Handling Functions

The IndyDCP3 C++ API provides several functions to handle different types of variables, such as boolean, integer, float, joint position (JPos), and task position (TPos) variables. These variables can be used to exchange information between the robot and external devices.

Method Description
get_bool_variable(std::vector<BoolVariable> &variables) Retrieves Bool type variables
get_int_variable(std::vector<IntVariable> &variables) Retrieves Integer type variables
get_float_variable(std::vector<FloatVariable> &variables) Retrieves Float type variables
get_jpos_variable(std::vector<JPosVariable> &variables) Retrieves JPos type variables
get_tpos_variable(std::vector<TPosVariable> &variables) Retrieves TPos type variables
set_bool_variable(const std::vector<BoolVariable> &variables) Sets Bool type variables
set_int_variable(const std::vector<IntVariable> &variables) Sets Integer type variables
set_float_variable(const std::vector<FloatVariable> &variables) Sets Float type variables
set_jpos_variable(const std::vector<JPosVariable> &variables) Sets JPos type variables
set_tpos_variable(const std::vector<TPosVariable> &variables) Sets TPos type variables

get_bool_variable() Example

This function retrieves the current values of Bool type variables from the robot.

std::vector<Nrmk::IndyFramework::BoolVariable> bool_vars;
bool is_success = indy.get_bool_variable(bool_vars);
if (is_success) {
    std::cout << "Bool variables retrieved successfully." << std::endl;
    for (const auto &var : bool_vars) {
        std::cout << "Address: " << var.addr() << ", Value: " << var.value() << std::endl;
    }
} else {
    std::cerr << "Failed to retrieve Bool variables." << std::endl;
}

get_int_variable() Example

This function retrieves the current values of Integer type variables from the robot.

std::vector<Nrmk::IndyFramework::IntVariable> int_vars;
bool is_success = indy.get_int_variable(int_vars);
if (is_success) {
    std::cout << "Integer variables retrieved successfully." << std::endl;
    for (const auto &var : int_vars) {
        std::cout << "Address: " << var.addr() << ", Value: " << var.value() << std::endl;
    }
} else {
    std::cerr << "Failed to retrieve Integer variables." << std::endl;
}

get_float_variable() Example

This function retrieves the current values of Float type variables from the robot.

std::vector<Nrmk::IndyFramework::FloatVariable> float_vars;
bool is_success = indy.get_float_variable(float_vars);
if (is_success) {
    std::cout << "Float variables retrieved successfully." << std::endl;
    for (const auto &var : float_vars) {
        std::cout << "Address: " << var.addr() << ", Value: " << var.value() << std::endl;
    }
} else {
    std::cerr << "Failed to retrieve Float variables." << std::endl;
}

get_jpos_variable() Example

This function retrieves the current values of Joint Position (JPos) type variables from the robot.

std::vector<Nrmk::IndyFramework::JPosVariable> jpos_vars;
bool is_success = indy.get_jpos_variable(jpos_vars);
if (is_success) {
    std::cout << "JPos variables retrieved successfully." << std::endl;
    for (const auto &var : jpos_vars) {
        std::cout << "Address: " << var.addr() << ", JPos: ";
        for (const auto &jpos : var.jpos()) {
            std::cout << jpos << " ";
        }
        std::cout << std::endl;
    }
} else {
    std::cerr << "Failed to retrieve JPos variables." << std::endl;
}

get_tpos_variable() Example

This function retrieves the current values of Task Position (TPos) type variables from the robot.

std::vector<Nrmk::IndyFramework::TPosVariable> tpos_vars;
bool is_success = indy.get_tpos_variable(tpos_vars);
if (is_success) {
    std::cout << "TPos variables retrieved successfully." << std::endl;
    for (const auto &var : tpos_vars) {
        std::cout << "Address: " << var.addr() << ", TPos: ";
        for (const auto &tpos : var.tpos()) {
            std::cout << tpos << " ";
        }
        std::cout << std::endl;
    }
} else {
    std::cerr << "Failed to retrieve TPos variables." << std::endl;
}

set_bool_variable() Example

This function sets the values of Bool type variables in the robot.

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 << "Bool variables set successfully." << std::endl;
} else {
    std::cerr << "Failed to set Bool variables." << std::endl;
}

set_int_variable() Example

This function sets the values of Integer type variables in the robot.

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 << "Integer variables set successfully." << std::endl;
} else {
    std::cerr << "Failed to set Integer variables." << std::endl;
}

set_float_variable() Example

This function sets the values of Float type variables in the robot.

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 << "Float variables set successfully." << std::endl;
} else {
    std::cerr << "Failed to set Float variables." << std::endl;
}

set_jpos_variable() Example

This function sets the values of Joint Position (JPos) type variables in the robot.

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 variables set successfully." << std::endl;
} else {
    std::cerr << "Failed to set JPos variables." << std::endl;
}

set_tpos_variable() Example

This function sets the values of Tool Position (TPos) type variables in the robot.

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 variables set successfully." << std::endl;
} else {
    std::cerr << "Failed to set TPos variables." << std::endl;
}

The IndyDCP3 C++ API provides functions for performing inverse kinematics, enabling/disabling direct teaching mode, setting simulation mode, and recovering the robot from error states.

Method Description
inverse_kin(const std::array<float, 6> &tpos, const std::vector<float> &init_jpos, std::vector<float> &jpos) Calculates joint positions to reach a target workspace position
set_direct_teaching(bool enable) Enables or disables direct teaching mode
set_simulation_mode(bool enable) Enables or disables simulation mode
recover() Recovers the robot from an error or collision state

inverse_kin() Example

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 << "Inverse kinematics successful. Joint positions: ";
    for (float jp : calculated_jpos) {
        std::cout << jp << " ";
    }
    std::cout << std::endl;
} else {
    std::cerr << "Inverse kinematics failed." << std::endl;
}

set_direct_teaching() Example

bool enable_direct_teaching = true;
bool is_success = indy.set_direct_teaching(enable_direct_teaching);
if (is_success) {
    std::cout << "Direct teaching mode enabled." << std::endl;
} else {
    std::cerr << "Failed to enable direct teaching mode." << std::endl;
}

set_simulation_mode() Example

bool enable_simulation = true;
bool is_success = indy.set_simulation_mode(enable_simulation);
if (is_success) {
    std::cout << "Simulation mode enabled." << std::endl;
} else {
    std::cerr << "Failed to enable simulation mode." << std::endl;
}

recover() Example

bool is_success = indy.recover();
if (is_success) {
    std::cout << "Recovery successful." << std::endl;
} else {
    std::cerr << "Recovery failed." << std::endl;
}

Program Control Functions

Program control functions allow you to start, pause, resume, and stop robot programs. These functions are essential for managing the execution flow of pre-written programs.

Method Description
play_program(const std::string &prog_name, int prog_idx) Starts a program by name or index
pause_program() Pauses the currently running program
resume_program() Resumes a paused program
stop_program() Stops the currently running program

play_program() Example

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 << "Program started successfully." << std::endl;
} else {
    std::cerr << "Failed to start program." << std::endl;
}

pause_program() Example

bool is_success = indy.pause_program();
if (is_success) {
    std::cout << "Program paused successfully." << std::endl;
} else {
    std::cerr << "Failed to pause program." << std::endl;
}

resume_program() Example

bool is_success = indy.resume_program();
if (is_success) {
    std::cout << "Program resumed successfully." << std::endl;
} else {
    std::cerr << "Failed to resume program." << std::endl;
}

stop_program() Example

bool is_success = indy.stop_program();
if (is_success) {
    std::cout << "Program stopped successfully." << std::endl;
} else {
    std::cerr << "Failed to stop program." << std::endl;
}

Using IndySDK

The IndyDCP3 C++ API provides functions to activate the IndySDK, set custom control modes, and manage control gains. These functions are crucial for advanced users who want to develop custom controllers.

Method Description
activate_sdk(const SDKLicenseInfo &request, SDKLicenseResp &response) Activates the IndySDK
set_custom_control_mode(bool mode) Sets the custom control mode
get_custom_control_mode(int &mode) Retrieves the current custom control mode
set_custom_control_gain(const CustomGainSet &gain_set) Sets custom control gain for the user controller
get_custom_control_gain(CustomGainSet &gain_set) Retrieves the current custom control gain settings

activate_sdk() Example

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 Activated: " << (response.activated() ? "Yes" : "No") << std::endl;
    std::cout << "Response Code: " << response.response().code() << ", Message: " << response.response().msg() << std::endl;
} else {
    std::cerr << "Failed to activate SDK." << std::endl;
}

set_custom_control_mode() and get_custom_control_mode() Example

int mode = 0;
bool is_success = indy.set_custom_control_mode(mode);
if (is_success) {
    std::cout << "Custom control mode set successfully." << std::endl;
} else {
    std::cerr << "Failed to set custom control mode." << std::endl;
}
int get_mode;
bool is_success = indy.get_custom_control_mode(get_mode);
if (is_success) {
    std::cout << "Custom control mode: " << get_mode << std::endl;
} else {
    std::cerr << "Failed to get custom control mode." << std::endl;
}

set_custom_control_gain() Example

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 << "Custom control gain set successfully." << std::endl;
} else {
    std::cerr << "Failed to set custom control gain." << std::endl;
}

get_custom_control_gain() Example

Nrmk::IndyFramework::CustomGainSet gain_set;
bool is_success = indy.get_custom_control_gain(gain_set);
if (is_success) {
    std::cout << "Custom control gains retrieved successfully." << 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 << "Failed to retrieve custom control gains." << std::endl;
}

Utility Functions

Utility functions provide additional features such as data logging and setting simulation mode.

Method Description
start_log() Starts realtime data logging
end_log() Ends and saves realtime data logging

start_log() and end_log() Example

bool is_success = indy.start_log();
if (is_success) {
    std::cout << "Started data logging." << std::endl;
}

// After some time...
is_success = indy.end_log();
if (is_success) {
    std::cout << "Ended data logging and saved data." << std::endl;
}

These two functions are used for realtime data logging. Upon calling start_log(), the robot's data is stored in memory. After a certain period, calling end_log() stops the memory logging and writes it to a file within STEP. The realtime data logging file can be found at the following path:

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

For more detailed usage and advanced features, please refer to C++ client at Neuromeka Github repository.