C++ IndyDCP client
C++ IndyDCP client is a C++ class for users to interface with Indy based on IndyDCP Protocol. Users can use every function by including single header file, IndyDCPConnector.h.
Installation
Please download the source file and project file for C++ IndyDCP client from the Download Page,making sure they match the version of the Indy SW you are using
C++ IndyDCP client has been tested and verified on both Windows and Linux. If you want to use IndyDCP client in a Windows environment, you can open the Visual Studio project located at the below path.
- /IndyDCPClientWindows/IndyDCPClientWindows.sln
Notes
If you encounter an error related to precompiled header in Visual Studio, try disabling the use of precompiled headers.
- In the project property menu, naviate to "Configuration Properties > C/C++ > Precompiled Header", then change the "Precompiled Header" setting to "Not Using Precompiled Headers".
Initializing and terminating socket
Before using C++ IndyDCP client, the socket library should be Initialized. Socket initialization and termination are handled in different ways in Windows and Linux.
Connecting to and disconnecting from your Indy
All communication with Indy can be done using the IndyDCPConnector class, defined in IndyDCPConnector.h. To initialize IndyDCPConnector, the IP address and name of the robot are required. All available robot names are defined in the namespace, NRMKIndy::Service::DCP.
#include "IndyDCPConnector.h"
using namespace NRMKIndy::Service::DCP;
//Initialize Indy
IndyDCPConnector connector("put.robot.ip.here", ROBOT_INDY7);
//connect to Indy
connector.connect()
///////////////////////
// Do task with Indy //
///////////////////////
//disconnect from Indy
connector.disconnect()
C++ IndyDCP Command List
The following shows examples of C++ IndyDCP commands. Commands not included in the example can be found in the complete command list. For more information about how to use this, please refer to the downloaded C ++ IndyDCP code.
Note
The return value of every method in **IndyDCPConnector** is an Integer, which represents an error code. The requested value are returned through references (call-by-reference).
Function | Description |
---|---|
stopEmergency() | Emergency stop |
resetRobot() | Reset robot |
setServoOnOff(const char * const servoVec) setServoOnOff(const bool * const servoVec) setServoOnOff(std::initializer_list |
Servo on/off depending on servoVec |
setBrakeOnOff(const char * const brakeVec) setBrakeOnOff(const bool * const brakeVec) setBrakeOnOff(std::initializer_list |
Brake on/off depending on brakeVec |
stopMotion() | Stop robot motion |
executeMoveCommand(const std::string & cmdName) | Execute Move command, named cmdName, taught by Conty |
moveJointHome() | Move Indy to the home position |
moveJointZero() | Move Indy to the zero position |
moveJointTo(const double * const qvec) moveJointTo(std::initializer_list |
Move each joint of Indy to the values in qvec |
moveJointBy(const double * const qvec) moveJointBy(std::initializer_list |
Move each joint of Indy to the values in qvec, relative to their current angles |
moveTaskTo(const double * const pvec) moveTaskTo(std::initializer_list |
Move end-effector of Indy to the 6 DoF position described by pvec |
moveTaskBy(const double * const pvec) moveTaskBy(std::initializer_list |
Move end-effector of Indy by the 6 DoF transformation described by pvec, relatively from to its current position |
startCurrProgram() | Execute the loaded robot program |
pauseProgram() | Pause robot program in currently running state |
resumeProgram() | Resume the paused robot program |
stopProgram() | Stop the robot program |
startRegisteredDefaultProgram() | Execute the registered default robot program |
registerDefaultProgram(int idx) | Register default robot program by an index 1 to 10 |
getRegisteredDefaultProgram(int &ret) | Request the registered default robot program's index |
isRobotRunning(bool& ret) | Check if robot software is runnig |
isRobotReady(bool& ret) | Check if robot is ready to move |
isEmergencyStopped(bool& ret) | Check if robot is stopped by emergency |
isCollided(bool& ret) | Check if robot is stopped by collision |
isErrorState(bool& ret) | Check if robot is in error state |
isBusy(bool& ret) | Check if robot is in motion |
isMoveFinished(bool& ret) | Check if robot is not moving |
isHome(bool& ret) | Check if robot is at the home position |
isZero(bool& ret) | Check if robot is at the zero position |
isInResetting(bool& ret) | Check if robot is restting |
isDirectTeachingMode(bool& ret) | Check if robot is in direct teaching mode |
isTeachingMode(bool& ret) | Check if robot is in teaching mode (direct teaching or jogging) |
isProgramRunning(bool& ret) | Check if robot is runnig a program |
isProgramPaused(bool& ret) | Check if robot program is paused |
isContyConnected(bool& ret) | Check if Conty is connected to the robot |
changeToDirectTeachingMode() | Start direct teaching mode |
finishDirectTeachingMode() | Terminate direct teaching mode |
addJointWaypointSet(const double * const qvec) addJointWaypointSet(std::initializer_list |
Add a joint waypoint |
removeJointWaypointSet() | Remove the last joint waypoint |
clearJointWaypointSet() | Clear all joint waypoints |
executeJointWaypointSet() | Start moving along the saved joint waypoints |
addTaskWaypointSet(const double * const pvec) addTaskWaypointSet(std::initializer_list |
Add an end-effector waypoint |
removeTaskWaypointSet() | Remove the last end-effector waypoint |
clearTaskWaypointSet() | Clear all end-effector waypoints |
executeTaskWaypointSet() | Start moving along the saved end-effector waypoints |
setDefaultTCP(const double * const tcpVec) setDefaultTCP(std::initializer_list |
Set default TCP value as tcpVec |
resetDefaultTCP() | Reset the default TCP value |
setTCPCompensation(const double * const tcpVec) setTCPCompensation(std::initializer_list |
Set TCP compensation value as tcpVec |
resetTCPCompensation() | Reset the TCP compensation value |
setReferenceFrame(const double * const refFrameVec) setReferenceFrame(std::initializer_list |
Set the Reference frame value as refFrameVec |
resetReferenceFrame() | Reset the Reference frame value |
setJointBoundaryLevel(int level) | Set the limit level of velocity/acceleration of JointMove (1-9) |
setTaskBoundaryLevel(int level) | Set the limit level of velocity/acceleration of TaskMove (1-9) |
setJointBlendingRadius(double radius) | Set blend radius of JointMove as radius |
setTaskBlendingRadius(double radius) | Set blend radius of TaskMove as radius |
setJointWaypointTime(double time) | Set travel time between waypoints of JointMove as time |
setTaskWaypointTime(double time) | Set travel time between waypoints of TaskMove as time |
setTaskBaseMode(int mode) | Set the base frame mode of TaskMove (0 = Reference frame, 1 = TCP frame) |
getDefaultTCP(double * const ret) | Request for default TCP value |
getTCPCompensation(double * const ret) | Request for TCP compensation value |
getReferenceFrame(double * const ret) | Request for Reference Frame value |
getCollisionDetectionLevel(int &ret) | Request for collision detection sensitivity level value |
getJointBoundaryLevel(int &ret) | Request for the limit level of velocity/acceleration of JointMove |
getTaskBoundaryLevel(int &ret) | Request for the limit level of velocity/acceleration of TaskMove |
getJointBlendingRadius(double &ret) | Request for the blend radius of JointMove |
getTaskBlendingRadius(double &ret) | Request for the blend radius of TaskMove |
getJointWaypointTime(double &ret) | Request for the travel time between waypoints of JointMove |
getTaskWaypointTime(double &ret) | Request for the travel time between waypoints of TaskMove |
getTaskBaseMode(int &ret) | Request for based frame mode of TaskMove |
getRobotRunningTime(double &ret) | Request for total runtime after robot initialization |
getControlMode(int &ret) | Request for current robot control mode |
getJointServoState(char * const ret) getJointServoState(char * const retServo, char * const retBrake) getJointServoState(bool * const retServo, bool * const retBrake) |
Request for status of servo and brake |
getJointPosition(double * const ret) | Request for current joint angles |
getJointVelocity(double * const ret) | Request for current joint angular velocity |
getTaskPosition(double * const ret) | Request for current task position |
getTaskVelocity(double * const ret) | Request for current task velocity |
getTorque(double * const ret) | Request for current robot torques |
getLastEmergencyInfo(int & retCode, int * const retIntArgs, double * const retDoubleArgs) | Request the latest emergency status information of the robot |
getSmartDigitalInput(int idx, char & ret) | Request value of idx-th DI channel. The result is stored in the reference variable ret |
getSmartDigitalInputs(char * const & ret) | Request all DI values.Each DI value is stored in each bit of ret |
setSmartDigitalOutput(int idx, char val) | Assign val value to the idx-th DO channel value |
setSmartDigitalOutputs(const char * const val) | Assign values to all DO channels. The value of each channel is assigned to each bit value of val |
getSmartDigitalOutput(int idx, char & ret) | Request value of idx-th DO channel. The result is stored in the reference variable ret |
getSmartDigitalOutputs(char * const & ret) | Request all DO values.Each DO value is stored in each bit of ret |
getSmartAnalogInput(int idx, int & ret) | Request idx-th AI channel values. The result is stored in ret (range 0-10000) |
setSmartAnalogOutput(int idx, int val) | Assign val value to idx-th AO channel value (range 0-10000) |
getSmartAnalogOutput(int idx, int & ret) | Request idx-th AI channel values. The result is stored in ret (range 0-10000) |
setEndtoolDigitalOutput(int endtoolType, char val) | Assign val value to the end-tool's DO with a type of endtoolType (endtoolType: 0 = NPN, 1 = PNP, 2 = Not use, 3 = eModi) |
getEndtoolDigitalOutput(int endtoolType, char & ret) | Request value of end-tool's DO with a type of endtoolType. The result is stored in the reference variable ret (endtoolType: 0 = NPN, 1 = PNP, 2 = Not use, 3 = eModi) |
getRobotCanFTSensorRaw(int * const ret) | Request for the raw data of FT sensor connected to robot end-tool CAN port |
getRobotCanFTSensorTransformed(double * const ret) | Request for transformed data value of FT sensor connected to robot end-tool CAN port |
getCBCanFTSensorRaw(int * const ret) | Request for raw data value of FT sensor connected to CAN port of control box |
getCBCanFTSensorTransformed(double * const ret) | Request for transformed data value of FT sensor connected to CAN port of control box |
readDirectVariable(int type, int addr, void * ret) | Read single value of direct variable with type type and addr address |
readDirectVariables(int type, int addr, int len, void * ret) | Read success value of len length of direct variable with type type and addr address |
writeDirectVariable(int type, int addr, void * ptrVal) | Write a single ptrVal value to a direct variable with type type and addr address |
writeDirectVariables(int type, int addr, int len, void * ptrVal) | Write consecutive ptrVal values len length to a direct variable with type type and addr address |
Units
- 6 DoF position is composed of 3 doubles for tranlations (x, y, z) and 3 doubles for orientation (θx, θy, θz). The rotation is applied in the order of z-y-x.
- The translations are in meters and orientations are in degrees.
- All joint angles are represented in degrees.
Simple motion & DIO example
In this section, an example code for simple robot motion and DIO control will be introduced. In this example, we assume the robot is the Indy7 and the robot's IP address is 192.168.0.100.
Warning
If you run the code, the robot will move! Clear the space around the robot.
#if defined (LINUX)
#include <unistd.h>
#elif defined (WINDOWS)
#pragma comment(lib,"ws2_32") //Must Link Winsock Library "ws2_32.dll"
#endif
#include <stdio.h>
#include <iostream>
#include "IndyDCPConnector.h"
using namespace std;
using namespace NRMKIndy::Service::DCP;
IndyDCPConnector connector("192.168.0.100", ROBOT_INDY7); // set the robot ip
void WaitFinish(IndyDCPConnector& connector) {
// Wait for motion finishing
bool fin = false;
do {
#if defined (LINUX)
sleep(0.5);
#elif defined(WINDOWS)
Sleep(500);
#endif
connector.isMoveFinished(fin); // check if motion finished
} while (!fin);
}
int main(int argc, char* argv[])
{
#if defined(WINDOWS)
initWinSock();
#endif
cout << "Connecting to the robot" << endl;
connector.connect();
bool ready;
connector.isRobotReady(ready);
if (ready) {
cout << "Robot is ready" << endl;
cout << "Go to zero position" << endl;
connector.moveJointZero();
WaitFinish(connector);
cout << "Go to home position" << endl;
connector.moveJointHome();
WaitFinish(connector);
double q[6];
cout << "Current joint values: " << endl;
connector.getJointPosition(q);
for(int i = 0;i<6;i++){ cout << q[i] << ","; }
cout << endl;
cout << "Rotate last joint by 10 degrees" << endl;
connector.moveJointBy({ 0,0,0,0,0,10 });
WaitFinish(connector);
cout << "Move joints to the saved values" << endl;
connector.moveJointTo(q);
WaitFinish(connector);
cout << "Move along waypoints" << endl;
connector.moveJointWaypointSet({
0, 0, 0, 0, 0, 0,
0, -15, -90, 0, -75, 0,
0, 0, 0, 0, 0, 0,
0, 15, 90, 0, 75, 0
});
WaitFinish(connector);
cout << "Current end-effector position:" << endl;
double p[6];
connector.getTaskPosition(p);
for (int i = 0; i < 6; i++) { cout << p[i] << ","; }
cout << endl;
cout << "Move end-effector upward by 5 cm" << endl;
connector.moveTaskBy({ 0,0,0.05,0,0,0 });
WaitFinish(connector);
cout << "Move end-effector to saved position" << endl;
connector.moveTaskTo(p);
WaitFinish(connector);
char ret;
cout << "Read DI 20: " << endl;
connector.getSmartDigitalInput(20, ret);
cout << ret << endl;
cout << "Write DO 4 as HIGH";
connector.setSmartDigitalOutput(4, 1);
cout << "Disconnecting robot" << endl;
connector.disconnect();
}
#if defined(WINDOWS)
cleanupWinSock(); // cleanup socket
#endif
}