C++
C++
This document will introduce the data types and APIs defined in the JAKA SDK (C++), mainly intended for software developers creating robot arm applications in C/C++ that communicate with virtual or real controllers. It will also be somewhat helpful for users who need to understand applications for JAKA robot arm controllers.
Interface List
robot Arm Basics
The following examples by default include the necessary header files, including "JAKAZuRobot.h" and native C++ header files.
robot Arm Control Class Constructor
robot Arm Control Class Constructor, all interfaces are contained within this class.
JAKAZuRobot();
Robot Arm Login
Connect to the robot arm controller. A successful start of this interface is the foundation for calling other interfaces.
- Parameter Description
- ip Controller IP address
- grpc_flag Whether to use the grpc interface. Default value is false, using the TCP interface
- username SDK username, default value is nullptr
- password SDK password, default value is nullptr, the jaka_sdk password set in the app
- Return Value ERR_SUCC Success Others indicate failure
errno_t login_in(const char *ip, bool grpc_flag = false, const char *username = nullptr, const char *password = nullptr);
Robot Arm Logout
Disconnect from the controller. Once this interface is successfully called, all functions except login_in cannot be called.
- Return Value ERR_SUCC Success Others indicate failure
errno_t login_out();
Power On Robot Arm
Turn on robot arm power
- Return Value ERR_SUCC Success Others indicate failure
errno_t power_on();
Power Off Robot Arm
Turn off robot arm power
- Return Value ERR_SUCC Success Others indicate failure
errno_t power_off();
Shut Down Robot Arm
Shut down robot arm control cabinet
- Return Value ERR_SUCC Success Others indicate failure
errno_t shut_down();
Enable Robot Arm
Enable control of the robot arm
- Return Value ERR_SUCC Success Others indicate failure
errno_t enable_robot();
Disable Robot Arm
Disable control of the robot arm
- Return Value ERR_SUCC Success Others indicate failure
errno_t disable_robot();
Control robot arm to enter or exit drag mode
Control the robot arm to enter or exit drag mode
- Parameter Description
- enable TRUE to enter drag mode, FALSE to exit drag mode
- Return Value ERR_SUCC Success Others indicate failure
errno_t drag_mode_enable(BOOL enable);
Query whether the robot arm is in drag mode
Query whether the robot arm is in drag mode
- Parameter Description
- in_drag Query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t is_in_drag_mode(BOOL *in_drag);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
int example_drag()
{
//Instantiate API object demo
JAKAZuRobot demo;
BOOL in_drag;
demo.is_in_drag_mode(&in_drag);
demo.drag_mode_enable(TRUE);
return 0;
}
Set joint friction compensation coefficient (drag feel parameter)
Deprecated interface
Set the friction compensation coefficient for each axis of the robot arm
- Parameter Description
- joint Joint number 0~5
- gain Friction compensation coefficient, value range 0-200, 200 compensates 200% of the friction
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_drag_friction_compensation_gain(int joint, int gain);
Get joint friction compensation coefficient
Get the friction compensation coefficient for each axis of the robot arm (drag feel parameter)
- Parameter Description
- list is a 6-dimensional integer array, corresponding to the friction compensation coefficients of 6 joints respectively
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_drag_friction_compensation_gain(DragFrictionCompensationGainList* list);
Default values for each joint of each model: (Zu7 = Zu5, Zu is the same as Pro and S)
| Robot Model | Joint 1 | Joint 2 | Joint 3 | Joint 4 | Joint 5 | Joint 6 | Note |
|---|---|---|---|---|---|---|---|
| Zu7 | 90 | 90 | 90 | 70 | 70 | 70 | |
| A7 | 90 | 90 | 90 | 70 | 70 | 70 | |
| Zu12 | 60 | 60 | 60 | 45 | 45 | 45 | |
| A12 | 60 | 60 | 60 | 45 | 45 | 45 | |
| Zu18 | 60 | 60 | 64 | 45 | 45 | 45 | |
| Zu3 | 45 | 45 | 45 | 60 | 60 | 60 | |
| Pro16 | 100 | 100 | 80 | 90 | 90 | 90 | |
| Zu20 | 100 | 100 | 80 | 60 | 60 | 60 | |
| MiniCobo | 5 | 5 | 5 | 10 | 10 | 10 | |
| Mini2 | 50 | 50 | 50 | 60 | 60 | 60 |
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
int example_drag()
{
//Example API object demo
JAKAZuRobot demo;
DragFrictionCompensationGainList list;
demo.get_drag_friction_compensation_gain(&list);
for(int i=0; i<6; i++){
std::cout << list.gain[i] << std::endl;
}
return 0;
}
Get SDK version number
Get robot arm controller version number
- Parameter Description
- version SDK version number
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_sdk_version(char *version);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get SDK version number
int example_getsdk_version()
{
//Instantiate API object demo
JAKAZuRobot demo;
char ver[100];
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Check the current SDK version
demo.get_sdk_version(ver);
std::cout << " SDK version is :" << ver << std::endl;
return 0;
}
Get SDK log path (static method)
Obtain the SDK log path, used before SDK object creation
- Parameter Description
- filepath SDK log path
- Return Value ERR_SUCC Success Others indicate failure
errno_t static_get_SDK_filepath(char *filepath);
Obtain SDK log path
Obtain SDK log path
- Parameter Description
- path SDK log path
- size length of the path
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_SDK_filepath(char* path, int size);
Set SDK log path (static method)
Deprecated interface
Set the SDK log path, used before SDK object creation
- Parameter Description
- filepath SDK log path
- Return Value ERR_SUCC Success Others indicate failure
errno_t static_set_SDK_filepath(char *filepath);
Set SDK log path
Set SDK log path
- Parameter Description
- filepath SDK log path
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_SDK_filepath(const char *filepath);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Set SDK log path
int example_set_SDK_filepath()
{
//Set SDK log path
char path[20] = "D://test.log";
errno_t ret;
JAKAZuRobot demo;
ret = demo.set_SDK_filepath(path);//Set SDK file path
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
std::cout << ret << std::endl;
return 0;
}
Set whether the SDK enables debug mode
Deprecated interface
Set whether to enable debug mode. If TRUE is selected, debug mode starts, and debugging information will be output to the standard output stream. If FALSE is selected, debugging information will not be output
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_debug_mode(BOOL mode);
Get controller IP
Get controller IP
- Parameter Description
- controller_name Controller name
- ip_list Controller IP list. When the controller name is a specific value, return the IP address corresponding to that name. When the controller name is empty, return all controller IP addresses within the subnet class.
- Return Value ERR_SUCC Success Others indicate failure
- When the app starts, this function becomes invalid
errno_t get_controller_ip(char *controller_name,char *ip_list);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get controller IP
int example_get_controller_ip()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
char ip_list[2000] = { 0 };
char controller_name1[50] = "";
//Get controller IP
ret = demo.get_controller_ip( controller_name1, ip_list);
std::cout << ret << std::endl;
std::cout << " ip_list is :" << ip_list << std::endl;
return 0;
}
Robot arm motion
Set the robot arm motion planner type
Set the type of planner used for robot arm motion
- Parameter Description
- type Motion planner type
- -1 Disable planner, use T planning by default
- 0 T planning, i.e., prioritize speed
- 1 S planning, i.e., prioritize smoothness
- type Motion planner type
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_motion_planner(MotionPlannerType type);
robot arm movement in manual mode
Control jog motion of the robot arm in manual mode
- Parameter Description
- aj_num Represents joint numbers [0-5 ]in joint space; in Cartesian space it corresponds to axes x, y, z, rx, ry, rz
- move_mode Robot arm motion mode. Available types: Absolute motion (ABS), incremental motion (INCR), continuous motion (CONTINUE), and stop (STOP)
- coord_type Robot arm motion coordinate system. Available systems: Tool coordinate system (COORD_TOOL), base coordinate system (COORD_BASE), or joint space (COORD_JOINT)
- vel_cmd Command speed. Unit for rotational axes or joint motion is rad/s; unit for linear axes is mm/s
- pos_cmd Command position, rotation axis or joint movement unit is rad, linear axis unit is mm. When move_mode is continuous, the parameter can be ignored
- Return value ERR_SUCC Success Others Failure
- Ps: When calling the jog function before reaching the target position, this position needs to be continuously sent
errno_t jog(int aj_num, MoveMode move_mode, CoordType coord_type, double vel_cmd, double pos_cmd);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <thread>
#define PI = 3.14159265358979323846
//Manual movement of robot arm
int main()
{
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
double value = PI/6;
JointValue joints;
while(TRUE){
demo.get_joint_position(&joints);
static double start = joints.jVal[1];
//Manual movement, where INCR represents incremental movement, 0.5 represents a speed of 0.5 rad/s
demo.jog(1, INCR, COORD_JOINT, 0.5, value);
if(std::abs(start + value - joints.jVal[1]) < 0.001){break;}
std::this_thread::sleep_for(std::chrono::milliseconds(100));
}
//Stop manual movement
demo.jog_stop(0);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
//Disable the robot arm
demo.disable_robot();
//Power off the robot arm
demo.power_off();
return 0;
}
robot arm stop movement in manual mode
Stop movement of the robot arm in manual mode
- Parameter Description
- num robot arm axis number 0-5, when num is -1, stop all axes
- Return Value ERR_SUCC Success Others indicate failure
errno_t jog_stop(int num);
robot arm joint movement
robot arm joint movement
- Parameter Description
- joint_pos Target position for robot arm joint movement, a double type 6-dimensional array
- move_mode Robot arm motion mode. Available types: Absolute motion (ABS), incremental motion (INCR), continuous motion (CONTINUE), and stop (STOP)
- is_block Set whether the interface is blocking, TRUE for blocking, FALSE for non-blocking, blocking has a default 30s timeout
- speed robot arm joint movement speed, unit: rad/s
- acc robot arm joint movement angular acceleration, default value is 3.5rad/s2
- tol robot arm joint movement endpoint error, this parameter makes transitions between two movements smoother. When using this parameter, multiple consecutive movements are required, and it must be in non-blocking mode. Default value is 0mm
- option_cond Optional parameters for robot arm joint movement, if not needed, this value can be left unassigned
- Return Value ERR_SUCC Success Others indicate failure
errno_t joint_move(const JointValue *joint_pos, MoveMode move_mode, BOOL is_block, double speed, double acc = 3.5, double tol = 0, const OptionalCond *option_cond= nullptr);
robot arm linear movement at end effector
robot arm end linear movement
- Parameter Description
- end_pos Target position for robot arm end movement
- tran In Cartesian space, target position for tool end movement, unit is mm, in order: x, y, z
- rpy In rotation axis space, target orientation for tool end movement, unit is rad, in order: rx, ry, rz
- move_mode Robot arm motion mode. Available types: Absolute motion (ABS), incremental motion (INCR), continuous motion (CONTINUE), and stop (STOP)
- is_block Set whether the interface is blocking, TRUE for blocking, FALSE for non-blocking, blocking has a default 30s timeout
- speed robot arm linear movement speed, unit: mm/s
- acc robot arm linear movement acceleration, default value is 500mm/s2
- tol robot arm linear movement endpoint error. This parameter makes transitions between two movements smoother. When using this parameter, multiple consecutive movements are required, and it must be in non-blocking mode. Default value is 0mm
- option_cond Optional parameters for robot arm linear movement, if not needed, this value can be left unassigned
- ori_vel Orientation velocity, default value is 3.14rad/s
- ori_acc Orientation acceleration, default value is 12.56rad/s2
- end_pos Target position for robot arm end movement
- Return Value ERR_SUCC Success Others indicate failure
- Three common cases where singularities occur:
- The tool’s end position lies in the plane formed by axes Z1 and Z2;
- Axes Z2, Z3, and Z4 are coplanar;
- Joint 5 angle is 0 or 180°, meaning Z4 and Z6 are parallel;
errno_t linear_move(const CartesianPose *end_pos, MoveMode move_mode, BOOL is_block, double speed, double accel = 500, double tol = 0, const OptionalCond *option_cond = nullptr, double ori_vel = 3.14, double ori_acc = 12.56);
Code example:
int example_linear_move()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
RobotStatus status;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Define and initialize the CartesianPose variable, with rotation angles in radians.
CartesianPose cart;
cart.tran.x = 300; cart.tran.y = 300; cart.tran.z = 100;
cart.rpy.rx = 3.14; cart.rpy.ry = 0 ; cart.rpy.rz = 0;
//Cartesian space motion, where ABS represents absolute motion, FALSE indicates the command is non-blocking, and 10 represents a speed of 10 mm/s
std::cout << "rx=" << cart.rpy.rx << " , ry=" << cart.rpy.ry<< " , rz=" << cart.rpy.rz << std::endl;
demo.linear_move(&cart, ABS, FALSE, 200, 10 ,1,NULL); //Move to a nearby point first to avoid passing through a singularity
for (int i = 3; i > 0;i--) {
cart.tran.x = 150; cart.tran.y = 300;
//Cartesian space extended motion, where ABS represents absolute motion, FALSE indicates the command is non-blocking, 20 is the maximum speed in mm/s, 10 is the acceleration in mm/s², and 5 is the arc transition radius in mm
demo.linear_move(&cart, ABS, FALSE, 20, 10, 5, NULL);
cart.tran.x = 150; cart.tran.y = 250;
demo.linear_move(&cart, ABS, FALSE, 20, 10, 5, NULL);
cart.tran.x = 225; cart.tran.y = 250;
demo.linear_move(&cart, ABS, FALSE, 20, 10, 5, NULL);
cart.tran.x = 300; cart.tran.y = 250;
demo.linear_move(&cart, ABS, FALSE, 20, 10, 5, NULL);
cart.tran.x = 300; cart.tran.y = 300;
demo.linear_move(&cart, ABS, FALSE, 20, 10, 5, NULL);
std::this_thread::sleep_for(std::chrono::milliseconds(3000));
}
demo.login_out();
return 0;
}
robot arm arc movement
Robot arm end circular arc motion, where this interface uses the current point and two input points to plan a circular trajectory.
- Parameter Description
- end_pos Target position for robot arm end movement
- tran In Cartesian space, target position for tool end movement, unit is mm, in order: x, y, z
- rpy Rotation axis space, target pose of the tool end movement, in radians, in the order of rx, ry, rz
- mid_pos Intermediate point of the robot arm end movement
- move_mode Robot arm motion mode. Available types: Absolute motion (ABS), incremental motion (INCR), continuous motion (CONTINUE), and stop (STOP)
- is_block Sets whether the interface is a blocking interface; TRUE for blocking interface, FALSE for non-blocking interface
- speed robot arm linear movement speed, unit: mm/s
- acc Acceleration of the robot arm in Cartesian space, unit: mm/s2
- tol Endpoint error of the robot arm movement in Cartesian space
- option_cond Optional parameters for robot arm joint movement, if not needed, this value can be left unassigned
- circle_cnt Specifies the number of circular motion loops for the robot arm. The default value is 0; when it is 0, it is equivalent to circular_move
- circle_mode Specifies the circular motion mode of the robot arm, default value is 0, parameter description as follows:
- 0: Fixed to use the axis-angle from start pose to end pose with rotation angle less than 180° for pose change. (Current scheme)
- 1: Fixed to use the axis-angle from start pose to end pose with rotation angle greater than 180° for pose change.
- 2: Automatically choose whether the angle is less than 180° or greater than 180° based on the midpoint pose.
- 3: The pose angle remains consistent with the arc axis at all times (current full circle motion).
- end_pos Target position for robot arm end movement
- Return value ERR_SUCC Success; others indicate failure
errno_t circular_move(const CartesianPose *end_pos, const CartesianPose *mid_pos, MoveMode move_mode, BOOL is_block, double speed, double accel, double tol, const OptionalCond *option_cond = nullptr, double circle_cnt = 0, int circle_mode = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#define PI 3.14159265358979323846
// robot arm circular motion, maximum joint speed 3.14 rad/s
int example_circle_move()
{
OptionalCond opt;
CartesianPose end_p, mid_p;
end_p.tran.x = -200; end_p.tran.y = 400; end_p.tran.z = 400;
end_p.rpy.rx = -PI/2; end_p.rpy.ry = 0; end_p.rpy.rz = 0;
mid_p.tran.x = -300; mid_p.tran.y = 400; mid_p.tran.z = 500;
mid_p.rpy.rx = -PI/2; mid_p.rpy.ry = 0; mid_p.rpy.rz = 0;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
// Define and initialize the JointValue variable
JointValue joint_pos = { 105.791*PI/180 , 63.471*PI/180 , -60.442*PI/180 , 176.971*PI/180 , 74.515*PI/180 , 0 };
//Joint space motion, where ABS represents absolute motion, TRUE means the command is blocking, and 1 represents a speed of 1 rad/s
demo.joint_move(&joint_pos, ABS, TRUE, 1);
//Circular motion, where ABS represents absolute motion, TRUE means the command is blocking, 20 represents a linear speed of 20 mm/s, 1 represents acceleration, 0.1 represents the mechanical arm's end-point error, opt is an optional parameter, and 3 means 3 rotations.
demo.circular_move(&end_p, &mid_p, ABS, TRUE, 20, 1, 0.1,&opt);
return 0;
}
Code Example 2:
#include "jktypes.h"
#include "JAKAZuRobot.h"
#define PI 3.14159265358979323846
int example_circular_move()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
CartesianPose start_pos {-251.054, -48.360, 374.000, 3.14, 0, 1.57}; // Starting point
CartesianPose mid_pos = {-400.054, -198.360, 374.000, 3.14, 0, 1.57}; // Midpoint
CartesianPose end_pos = {-251.054, -348.360, 374.000, 3.14, 0, 1.57}; // Endpoint
demo.jog_stop(-1); // Stop current joint motion
JointValue ref_jv {0, 90*PI/180, 90*PI/180, 90*PI/180, -90*PI/180, 0}; // First move near the starting point
demo.joint_move(&ref_jv, MoveMode::ABS, true, 20);
JointValue start_jv;
demo.get_joint_position(&ref_jv); // Get the current joint angles
demo.kine_inverse(&ref_jv, &start_pos, &start_jv); // Use the current joint angles as a reference to calculate the starting joint angles
demo.joint_move(&start_jv, MoveMode::ABS, true, 80); // Move to the starting joint angle position
OptionalCond opt;
// Specify rotation for 3 circles
demo.circular_move(&end_pos, &mid_pos, MoveMode::ABS, true, 120, 100, 0.1, &opt, 3);
demo.disable_robot();
demo.power_off();
demo.login_out();
}
Terminate robot arm movement
Terminate current robot arm motion, the robot arm script program will also stop
- Return Value ERR_SUCC Success Others indicate failure
errno_t motion_abort();
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <thread>
#define PI 3.14159265358979323846
//Terminate robot arm movement
int example_motion_abort()
{
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
// Define and initialize the JointValue variable
printf("start_move");
JointValue joint_pos = { 0 , 0 , 50*PI/180 , 0 , 0 , 0 };
//Joint space motion, where ABS represents absolute motion, TRUE means the command is blocking, and 1 represents a speed of 1 rad/s
demo.joint_move(&joint_pos, ABS, FALSE, 1);
std::this_thread::sleep_for(std::chrono::milliseconds(5000));
//Terminate after moving for 5s
demo.motion_abort();
printf("stop_move");
return 0;
}
Check if the robot arm movement has stopped
Query whether the robot arm movement has stopped
- Parameter Description
- in_pos Query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t is_in_pos(BOOL *in_pos);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <thread>
//Query whether the robot arm movement has stopped
int example_is_in_pos()
{
//Instantiate API object demo
JAKAZuRobot demo;
BOOL in_pos;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
while (1)
{
//Query whether movement has stopped
demo.is_in_pos(&in_pos);
std::cout << " in_pos is :" << in_pos << std::endl;
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
}
return 0;
}
Check the robot arm motion status
Query the robot arm movement status.
- Parameter description
- status robot arm movement status
- motion_line ID of the current motion command
- motion_line_sdk Reserved parameter
- inpos Whether the current movement is completed
- err_add_line Failed to add motion command (robot arm is already at the target position)
- queue Number of motion commands waiting to be processed in the queue
- active_queue Number of commands currently in motion in the queue
- queue_full Whether the command queue is full, 0: queue not full, 1: queue full
- paused Whether the robot arm is paused, 0: robot arm not paused, 1: robot arm paused
- isOnLimit Whether the robot arm is in soft limit mode, 0: robot arm normal, 1: robot arm reached soft limit
- isInEstop Whether the robot arm is in emergency stop mode, 0: robot arm normal, 1: robot arm in emergency stop
- isInCollision Whether the robot arm is in collision state, 0: robot arm normal, 1: robot arm triggered collision
- status robot arm movement status
errno_t get_motion_status(MotionStatus *status);
External axis motion
Enable on external axis
Enable on external axis
- Parameter Description
- ext_id External axis ID
- Return Value ERR_SUCC Success Others indicate failure
errno_t enable_ext(int ext_id);
Disable on external axis
Disable on external axis
- Parameter Description
- ext_id External axis ID
- Return Value ERR_SUCC Success Others indicate failure
errno_t disable_ext(int ext_id);
Get external axis status
Get external axis status
- Parameter Description
- status_list External axis status list
- ext_id External axis ID, -1 means get all external axis statuses
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_ext_status(ExtAxisStatusList *status_list, int ext_id = -1);
External axis jog motion
External axis jog motion
- Parameter Description
- ext_id External axis ID, -1 means get all external axis statuses
- is_abs 0 means absolute motion ABS, 1 means incremental motion INCR, 2 means continuous motion CONTINUE
- vel Speed, incremental and continuous motion direction is controlled by speed
- step ABS: step is target position; INCR: step is target increment; CONTINUE: step has no meaning
- Return Value ERR_SUCC Success Others indicate failure
errno_t jog_ext(int ext_id, int is_abs, double vel, double step);
External axis combined motion
Get external axis status
- Parameter Description
- status_list External axis status list (when the external axis is in joint motion, the unit is radians rad; when the external axis is in linear motion, the unit is millimeters mm)
- ext_id External axis ID, -1 means get all external axis statuses
- Return Value ERR_SUCC Success Others indicate failure
errno_t multi_mov_with_ext(MultiMovInfoList multi_mov_info_list, DI_Info *di_info, int plannertype);
Code example:
#include <iostream>
#include <thread>
#include <math.h>
#include "JAKAZuRobot.h"
#define rad2deg(x) ((x)*180.0/M_PI)
#define deg2rad(x) ((x)*M_PI/180.0)
void jog_ext();
void move_ext();
void movej_with_ext();
void movel_with_ext();
void movec_with_ext();
JAKAZuRobot robot;
errno_t ret;
int main()
{
//Initialization, power on and enable
ret = robot.login_in("192.168.220.144",1,"jaka_sdk","Jaka123@");
if(ret==0){std::cout << "Login successful" << std::endl;}
else {std::cout << "Login failed" << std::endl;}
robot.power_on();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
robot.enable_robot();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
JointValue jpos = {0, deg2rad(90), deg2rad(90), deg2rad(90), deg2rad(-90), deg2rad(10)};
robot.joint_move(&jpos, ABS, true, 10);
std::cout << "Initial position completed" << std::endl;
robot.enable_ext(0);
std::cout << "enable_ext completed" << std::endl;
jog_ext();
move_ext();
movej_with_ext();
movel_with_ext();
movec_with_ext();
robot.login_out();
return 0;
}
void jog_ext()
{
std::cout << " jog_ext" << std::endl;
robot.set_auto_manual_mode(false);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
robot.jog_ext(0,0,80,5);
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
robot.jog_ext(0,0,80,4);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
robot.jog_stop(-1);
robot.jog_ext(0,1,80,1);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
robot.jog_stop(-1);
robot.jog_ext(0,1,-80,1);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
robot.jog_ext(0,2,1,0);
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
robot.jog_stop(-1);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
robot.jog_ext(0,2,-1,0);
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
robot.jog_stop(-1);
robot.set_auto_manual_mode(true);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
}
void move_ext()
{
std::cout << "Separate external axis movement" << std::endl;
MultiMovInfoList move_ext;
move_ext.count = 1;
move_ext.is_block = 1;
move_ext.multi_mov_info[0].motion_unit_type = 1;
move_ext.multi_mov_info[0].move_type = 0;
move_ext.multi_mov_info[0].motion_unit_id = 0;
move_ext.multi_mov_info[0].end_pos[0] = 100;
move_ext.multi_mov_info[0].move_mode = 0;
move_ext.multi_mov_info[0].j_vel = 80;
move_ext.multi_mov_info[0].j_acc = 80;
move_ext.multi_mov_info[0].radius = 0.0;
ret = robot.multi_mov_with_ext(move_ext);
std::cout << "Individual external axis movement finished 1" << std::endl;
move_ext.multi_mov_info[0].end_pos[0] = 200;
ret = robot.multi_mov_with_ext(move_ext);
std::cout << "Individual external axis movement finished 2" << std::endl;
move_ext.multi_mov_info[0].end_pos[0] = 0;
ret = robot.multi_mov_with_ext(move_ext);
std::cout << "Individual external axis movement finished 3" << std::endl;
}
void movej_with_ext()
{
std::cout << "Joint movement + external axis movement" << std::endl;
MultiMovInfoList movej_info;
movej_info.count = 2;
movej_info.is_block = 1;
movej_info.multi_mov_info[0].motion_unit_type = 1;
movej_info.multi_mov_info[0].move_type = 0;
movej_info.multi_mov_info[0].motion_unit_id = 0;
movej_info.multi_mov_info[0].end_pos[0] = 100;
movej_info.multi_mov_info[0].move_mode = 0;
movej_info.multi_mov_info[0].j_vel = 80;
movej_info.multi_mov_info[0].j_acc = 80;
movej_info.multi_mov_info[0].radius = 0.0;
movej_info.multi_mov_info[1].motion_unit_type = 0;
movej_info.multi_mov_info[1].move_type = 0;
movej_info.multi_mov_info[1].motion_unit_id = 0;
movej_info.multi_mov_info[1].end_pos[0] = deg2rad(90);
movej_info.multi_mov_info[1].end_pos[1] = deg2rad(90);
movej_info.multi_mov_info[1].end_pos[2] = deg2rad(90);
movej_info.multi_mov_info[1].end_pos[3] = deg2rad(90);
movej_info.multi_mov_info[1].end_pos[4] = deg2rad(-90);
movej_info.multi_mov_info[1].end_pos[5] = 0;
movej_info.multi_mov_info[1].move_mode = 0;
movej_info.multi_mov_info[1].j_vel = deg2rad(80);
movej_info.multi_mov_info[1].j_acc = deg2rad(200);
movej_info.multi_mov_info[1].radius = 0.0;
ret = robot.multi_mov_with_ext(movej_info);
std::cout << "Joint movement + external axis movement finished 1" << std::endl;
movej_info.multi_mov_info[0].end_pos[0] = 0;
movej_info.multi_mov_info[1].end_pos[0] = deg2rad(0);
ret = robot.multi_mov_with_ext(movej_info);
std::cout << "Joint movement + external axis movement finished 2" << std::endl;
}
void movel_with_ext()
{
std::cout << "Linear movement + external axis movement" << std::endl;
MultiMovInfoList multi_mov_info_list;
multi_mov_info_list.count = 2;
multi_mov_info_list.is_block = TRUE;
multi_mov_info_list.multi_mov_info[0].motion_unit_type = 1;
multi_mov_info_list.multi_mov_info[0].move_type = 0;
multi_mov_info_list.multi_mov_info[0].motion_unit_id = 0;
multi_mov_info_list.multi_mov_info[0].end_pos[0] = 100;
multi_mov_info_list.multi_mov_info[0].vel = 80;
multi_mov_info_list.multi_mov_info[0].acc = 80;
multi_mov_info_list.multi_mov_info[1].motion_unit_type = 0;
multi_mov_info_list.multi_mov_info[1].move_type = 1;
multi_mov_info_list.multi_mov_info[1].motion_unit_id = 0;
multi_mov_info_list.multi_mov_info[1].end_pos[0] = 0;
multi_mov_info_list.multi_mov_info[1].end_pos[1] = -300;
multi_mov_info_list.multi_mov_info[1].end_pos[2] = 300;
multi_mov_info_list.multi_mov_info[1].end_pos[3] = deg2rad(-180);
multi_mov_info_list.multi_mov_info[1].end_pos[4] = deg2rad(0);
multi_mov_info_list.multi_mov_info[1].end_pos[5] = deg2rad(180);
multi_mov_info_list.multi_mov_info[1].vel = 80;
multi_mov_info_list.multi_mov_info[1].acc = 80;
multi_mov_info_list.multi_mov_info[1].ori_vel = deg2rad(180);
multi_mov_info_list.multi_mov_info[1].ori_acc = deg2rad(720);
ret = robot.multi_mov_with_ext(multi_mov_info_list);
std::cout << "Linear motion + external axis motion finished 1" << std::endl;
multi_mov_info_list.multi_mov_info[0].end_pos[0] = 0;
multi_mov_info_list.multi_mov_info[1].end_pos[0] = -300;
multi_mov_info_list.multi_mov_info[1].end_pos[1] = 100;
multi_mov_info_list.multi_mov_info[1].end_pos[2] = 300;
ret = robot.multi_mov_with_ext(multi_mov_info_list);
std::cout << "Linear motion + external axis motion finished 2" << std::endl;
}
void movec_with_ext()
{
std::cout << "Arc motion + external axis motion" << std::endl;
MultiMovInfoList multi_mov_info_list;
multi_mov_info_list.count = 2;
multi_mov_info_list.is_block = TRUE;
multi_mov_info_list.multi_mov_info[0].motion_unit_type = 1;
multi_mov_info_list.multi_mov_info[0].move_type = 0;
multi_mov_info_list.multi_mov_info[0].motion_unit_id = 0;
multi_mov_info_list.multi_mov_info[0].end_pos[0] = 100;
multi_mov_info_list.multi_mov_info[0].vel = 80;
multi_mov_info_list.multi_mov_info[0].acc = 80;
multi_mov_info_list.multi_mov_info[1].motion_unit_type = 0;
multi_mov_info_list.multi_mov_info[1].move_type = 2;
multi_mov_info_list.multi_mov_info[1].motion_unit_id = 0;
multi_mov_info_list.multi_mov_info[1].mid_pos.tran.x = -145.178;
multi_mov_info_list.multi_mov_info[1].mid_pos.tran.y = 15.344;
multi_mov_info_list.multi_mov_info[1].mid_pos.tran.z = 291.208;
multi_mov_info_list.multi_mov_info[1].mid_pos.rpy.rx = deg2rad(179.943);
multi_mov_info_list.multi_mov_info[1].mid_pos.rpy.ry = deg2rad(0);
multi_mov_info_list.multi_mov_info[1].mid_pos.rpy.rz = deg2rad(89.694);
multi_mov_info_list.multi_mov_info[1].end_pos[0] = -345.178;
multi_mov_info_list.multi_mov_info[1].end_pos[1] = 15.344;
multi_mov_info_list.multi_mov_info[1].end_pos[2] = 291.208;
multi_mov_info_list.multi_mov_info[1].end_pos[3] = deg2rad(179.943);
multi_mov_info_list.multi_mov_info[1].end_pos[4] = deg2rad(0);
multi_mov_info_list.multi_mov_info[1].end_pos[5] = deg2rad(89.694);
multi_mov_info_list.multi_mov_info[1].vel = 80;
multi_mov_info_list.multi_mov_info[1].acc = 200;
multi_mov_info_list.multi_mov_info[1].ori_vel = deg2rad(180);
multi_mov_info_list.multi_mov_info[1].ori_acc = deg2rad(720);
ret = robot.multi_mov_with_ext(multi_mov_info_list);
std::cout << "Arc motion + external axis motion finished 1" << std::endl;
multi_mov_info_list.multi_mov_info[0].end_pos[0] = 0;
multi_mov_info_list.multi_mov_info[1].end_pos[0] = -300;
multi_mov_info_list.multi_mov_info[1].end_pos[1] = 100;
multi_mov_info_list.multi_mov_info[1].end_pos[2] = 300;
multi_mov_info_list.multi_mov_info[1].end_pos[3] = deg2rad(-180);
multi_mov_info_list.multi_mov_info[1].end_pos[4] = deg2rad(0);
multi_mov_info_list.multi_mov_info[1].end_pos[5] = deg2rad(180);
ret = robot.multi_mov_with_ext(multi_mov_info_list);
std::cout << "Arc motion + external axis motion finished 2" << std::endl;
}
Robot arm operation information setting and retrieval
Retrieve robot arm status monitoring data (only thread-safe interface)
Retrieve robot arm status data, thread-safe
- Parameter Description
- status Robot arm status
- errcode Robot arm error code, 0: no error
- inpos Whether the robot arm motion is completed, 0: motion not completed, 1: motion completed
- powered_on Whether the robot arm is powered on, 0: not powered on, 1: powered on
- enabled Whether the robot arm is enabled, 0: not enabled, 1: enabled
- rapidrate Robot arm motion speed ratio
- protective_stop Whether the robot arm has detected a collision, 0: normal, 1: collision triggered
- emergency_stop Whether the robot arm has performed an emergency stop, 0: normal, 1: in emergency stop state
- dout Digital output signals of the robot arm control cabinet, [dout0 ]is the number of signals
- din Digital input signals of the robot arm control cabinet, [din0 ]is the number of signals
- ain Analog input signals of the robot arm control cabinet, [ain0 ]is the number of signals
- aout Analog output signals of the robot arm control cabinet, [aout0 ]is the number of signals
- tio_dout Digital output signals of the robot arm end tool, [tio_dout0 ]is the number of signals
- tio_din Digital input signals of the robot arm end tool, [tio_din0 ]is the number of signals
- tio_ain Analog input signals of the robot arm end tool, [tio_ain0 ]is the number of signals
- tio_key Three button states of the robot arm end tool, [0free]; [1point]; [2pause_resume]
- extio External application IO of the robot arm
- modbus_slave Robot arm Modbus slave
- profinet_slave Robot arm Profinet slave
- eip_slave Robot arm Ethernet/IP slave
- current_tool_id ID of the currently used tool coordinate system
- cartesiantran_position Position of the robot end tool in Cartesian space
- joint_position Position in the robot joint space
- on_soft_limit Whether the robot arm is at the soft limit, 0: robot arm normal, 1: robot arm reached soft limit
- current_user_id ID of the currently used user coordinate system
- drag_status Whether the robot arm is in drag mode, 0: robot arm normal, 1: robot arm in drag mode
- robot_monitor_data Robot arm status monitoring data
- torq_sensor_monitor_data Robot arm torque sensor status monitoring data
- is_socket_connect Controller connection status, 0: controller connection abnormal, 1: controller connection normal
- status Robot arm status
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_robot_status(RobotStatus *status);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get robot arm status monitoring data
int example_get_robot_status()
{
//Instantiate API object demo
JAKAZuRobot demo;
RobotStatus robstatus;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
//Get robot arm status monitoring data
demo.get_robot_status(&robstatus);
demo.login_out();
return 0;
}
Get Robot Arm Status Monitoring Data
Retrieve robot arm status data, thread-safe
- Parameter Description
- status Robot arm status
- error robot arm error code, 0 means no error
- errmsg robot arm error message
- powered_on Whether the robot arm is powered on, 0: not powered on, 1: powered on
- enabled Whether the robot arm is enabled, 0: not enabled, 1: enabled
- status Robot arm status
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_robot_status_simple(RobotStatus_simple *status);
Get current robot arm joint angles — servo feedback
Get the current robot arm joint angles, save the joint angle matrix in the input parameter joint_position
- Parameter Description
- joint_position Joint angle query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_actual_joint_position(JointValue *joint_position);
Get the current robot arm joint angles
Get the current robot arm joint angles, save the joint angle matrix in the input parameter joint_position
- Parameter Description
- joint_position Joint angle query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_joint_position(JointValue *joint_position);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get current robot arm joint angles
int example_get_joint_position()
{
//Instantiate API object demo
JAKAZuRobot demo;
JointValue jot_pos;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Get current joint angles
demo.get_joint_position(&jot_pos);
for (int i = 0; i < 6; i++)
{
std::cout << "joint [" << i+1 << "] is :" << jot_pos.jVal[i] << std::endl;
}
return 0;
}
Set manual or automatic mode
Set the robot arm operation mode. In automatic mode, safety-related settings for the robot arm cannot be made; in manual mode, it will automatically enter retraction mode to ensure operational safety.
- Parameter Description
- mode Mode parameter, 0: manual mode, 1: automatic mode
- robot_id Robot ID, default is 0
- Return value ERR_SUCC Success Others Failure
errno_t set_auto_manual_mode(int mode, int robot_id = 0);
Get the current robot arm operation mode
Get the current robot arm operation mode
- Parameter Description
- mode Mode parameter, 0: manual mode, 1: automatic mode
- robot_id Robot ID, default is 0
- Return value ERR_SUCC Success Others Failure
errno_t get_auto_manual_mode(int *mode, int robot_id = 0);
Set the automatic update interval for robot arm status data
Deprecated interface
Set the automatic update interval for robot arm status data, specifically get_robot_status()
- Parameter Description
- Millisecond time parameter, unit: ms
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_status_data_update_time_interval(float millisecond);
Get the pose of the tool endpoint under the current settings — servo feedback
Get the pose of the tool’s end under the current settings, and store the pose in the input parameter tcp_position
- Parameter Description
- tcp_position Tool end pose query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_actual_tcp_position(CartesianPose *tcp_position);
Get the pose of the tool endpoint under the current settings
Get the pose of the tool’s end under the current settings, and store the pose in the input parameter tcp_position
- Parameter Description
- tcp_position Tool end pose query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_tcp_position(CartesianPose *tcp_position);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get tool end pose
int example_get_tcp_position()
{
//Instantiate API object demo
JAKAZuRobot demo;
CartesianPose tcp_pos;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Get tool end pose
demo.get_tcp_position(&tcp_pos);
std::cout << "tcp_pos is :n x: " << tcp_pos.tran.x << " y: " << tcp_pos.tran.y << " z: " << tcp_pos.tran.z << std::endl;
std::cout << "rx: " << tcp_pos.rpy.rx << " ry: " << tcp_pos.rpy.ry << " rz: " << tcp_pos.rpy.rz << std::endl;
return 0;
}
Set user coordinate system information
Set the user coordinate system information for the specified ID
- Parameter Description
- id User coordinate system ID, value range [1–15], 0 is the default world coordinate system and cannot be changed.
- user_frame User coordinate system offset value
- name User coordinate system alias
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_user_frame_data(int id, const CartesianPose *user_frame, const char *name);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//View and adjust user coordinate system
int example_user_frame()
{
int id_ret, id_set;
id_set = 2;
CartesianPose tcp_ret, tcp_set;
char name[50] = "test";
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
//Query the user coordinate system ID currently in use
demo.get_user_frame_id(&id_ret);
//Get the information of the user coordinate system currently in use
demo.get_user_frame_data(id_ret, &tcp_ret);
std::cout << "id_using=" << id_ret << " nx=" << tcp_ret.tran.x << " y=" << tcp_ret.tran.y << " z=" << tcp_ret.tran.y << std::endl;
std::cout << "rx=" << tcp_ret.rpy.rx << " y=" << tcp_ret.rpy.ry << " z=" << tcp_ret.rpy.rz << std::endl;
//Initialize the user coordinate system coordinates
tcp_set.tran.x = 0; tcp_set.tran.y = 0; tcp_set.tran.z = 10;
tcp_set.rpy.rx = 120 ; tcp_set.rpy.ry = 90 ; tcp_set.rpy.rz = -90 ;
//Set the user coordinate system information
demo.set_user_frame_data(id_set, &tcp_set, name);
//Switch to the user coordinate system coordinates currently in use
demo.set_user_frame_id(id_set);
//Query the user coordinate system ID currently in use
demo.get_user_frame_id(&id_ret);
//Get the information of the set user coordinate system
demo.get_user_frame_data(id_ret, &tcp_ret);
std::cout << "id_using=" << id_ret << " nx=" << tcp_ret.tran.x << " y=" << tcp_ret.tran.y << " z=" << tcp_ret.tran.y << std::endl;
std::cout << "rx=" << tcp_ret.rpy.rx << " y=" << tcp_ret.rpy.ry << " z=" << tcp_ret.rpy.rz << std::endl;
return 0;
}
Get user coordinate system information
Query the information of the user coordinate system currently in use
- Parameter Description
- id User coordinate system ID
- user_frame User coordinate system offset value
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_user_frame_data(int id, CartesianPose *user_frame);
Set the user coordinate system ID currently in use
Set the user coordinate system ID currently in use
- Parameter Description
- id User coordinate system ID, value range is [0 to 15], where 0 is the world coordinate system
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_user_frame_id(const int id);
Query the user coordinate system ID currently in use
Query the user coordinate system ID currently in use
- Parameter Description
- id Result obtained
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_user_frame_id(int *id);
Set tool information
Configure the tool information for the specified ID
- Parameter Description
- id Tool ID, value range [1 to 15]
- tcp Tool coordinate system offset relative to the flange coordinate system
- name Alias for the specified tool
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_tool_data(int id, const CartesianPose *tcp, const char *name);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//View and adjust tool coordinate system
int example_tool()
{
int id_ret, id_set;
id_set = 2;
CartesianPose tcp_ret, tcp_set;
char name[50] = "test";
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
//Query the ID of the currently used tool
demo.get_tool_id(&id_ret);
//Get information of the currently used tool
demo.get_tool_data(id_ret,&tcp_ret);
std::cout << "id_using=" << id_ret << " x=" << tcp_ret.tran.x << " y=" << tcp_ret.tran.y << " z=" << tcp_ret.tran.y << std::endl;
std::cout << "rx=" << tcp_ret.rpy.rx << " ry=" << tcp_ret.rpy.ry << " rz=" << tcp_ret.rpy.rz << std::endl;
//Initialize tool coordinates
tcp_set.tran.x = 0; tcp_set.tran.y = 0; tcp_set.tran.z = 10;
tcp_set.rpy.rx = 120 ; tcp_set.rpy.ry = 90 ; tcp_set.rpy.rz = -90 ;
//Set tool information
demo.set_tool_data(id_set, &tcp_set, name);
//Switch the currently used tool coordinates
demo.set_tool_id(id_set);
//Query the ID of the currently used tool
demo.get_tool_id(&id_ret);
//Get the information of the set tool
demo.get_tool_data(id_ret, &tcp_ret);
std::cout << "id_using=" << id_ret << " nx=" << tcp_ret.tran.x << " y=" << tcp_ret.tran.y << " z=" << tcp_ret.tran.y << std::endl;
std::cout << "rx=" << tcp_ret.rpy.rx << " ry=" << tcp_ret.rpy.ry << " rz=" << tcp_ret.rpy.rz << std::endl;
return 0;
}
Get tool information
Query the information of the currently used tool, refer to the example for setting tool information
- Parameter Description
- id Tool ID query result
- tcp Tool coordinate system offset relative to the flange coordinate system
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_tool_data(int id, CartesianPose *tcp);
Query the currently used tool ID
Query the currently used tool ID
- Parameter Description
- id Tool ID query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_tool_id(int *id);
Set the currently used tool ID
Set the currently used tool ID. When there are network fluctuations, after switching the ID, it takes some delay to take effect.
- Parameter Description
- id Tool coordinate system ID, value range is [0–15], where 0 means using the default end flange center coordinate system
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_tool_id(const int id);
Set digital output variable
Set the value of a digital output variable (DO)
- Parameter Description
- type DO type
- IO_CABINET, controller IO
- IO_TOOL, tool IO
- IO_EXTEND, extended IO
- IO_REALY, relay IO, only supported by Cabv3
- IO_MODBUS_SLAVE, Modbus slave IO
- IO_PROFINET_SLAVE, Profinet slave IO
- IO_EIP_SLAVE, ETHERNET/IP slave IO
- index DO index (starting from 0)
- value DO value to set
- type DO type
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_digital_output(IOType type, int index, BOOL value);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <thread>
//Set and query digital output
int main()
{
BOOL DO3;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Query the status of DO3
demo.get_digital_output(IO_CABINET, 2, &DO3);
std::cout << "D03 = " << DO3 << std::endl;
//io_cabinet is the controller cabinet panel IO, 2 represents DO3, and 1 corresponds to the DO value to be set.
demo.set_digital_output(IO_CABINET, 2, 1);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));//Need to delay 1s
//Query the status of DO3
demo.get_digital_output(IO_CABINET, 2, &DO3);
std::cout << "D03 = " << DO3 << std::endl;
return 0;
}
Set analog output variable
Set the value of the analog output variable (AO)
- Parameter Description
- type AO type, optional types refer to
setting digital output variables; when acting as a Modbus slave IO, the index is 4 - index AO index (starting from 0)
- value AO set value
- type AO type, optional types refer to
- Return value ERR_SUCC Success Others Failure
- Ps: The V3 version does not currently support control cabinet type analog IO, when using it the type cannot be set to control cabinet IO
errno_t set_analog_output(IOType type, int index, float value);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <thread>
//Set and query analog output
int main()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
demo.power_on();
float AO1;
//Query AO status
demo.get_analog_output(IO_MODBUS_SLAVE, 0, &AO1);
std::cout << "AO1 = " << AO1 << std::endl;
//IO_MODBUS_SLAVE is Modbus IO, 0 represents AO1, 1.5 corresponds to the AO value to be set.
demo.set_analog_output(IO_MODBUS_SLAVE, 0, 2);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
//Query AO status
demo.get_analog_output(IO_MODBUS_SLAVE, 0, &AO1);
std::cout << "AO1 = " << AO1 << std::endl;
return 0;
}
Set digital output variable during movement
Set the value of the digital output variable (DO) during motion
- Parameter Description
- type DO type, optional types refer to
setting digital output variables - index DO index (starting from 0)
- value DO value to set
- rel 0: relative to the motion start point, 1: relative to the motion end point
- distance Distance, refers to how far from the start or end point (based on the rel parameter) to trigger DO
- type DO type, optional types refer to
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_motion_digital_output(IOType type, int index, BOOL value, BOOL rel, double distance);
Set analog output variable during movement
Set the value of the analog output variable (AO) during motion
- Parameter Description
- type AO type, optional types refer to
setting digital output variables - index AO index (starting from 0)
- value AO set value
- rel 0: relative to the motion start point, 1: relative to the motion end point
- distance Distance, refers to how far from the start or end point (based on the rel parameter) to trigger AO
- type AO type, optional types refer to
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_motion_analog_output(IOType type, int index, BOOL value, BOOL rel, double distance);
Check digital input status
Query digital input (DI) status
- Parameter Description
- type DI type, optional types refer to
setting digital output variables - index DI index (starting from 0)
- result DI status query result
- type DI type, optional types refer to
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_digital_input(IOType type, int index, BOOL *result);
Check digital output status
Query digital output (DO) status
- Parameter Description
- type DO type, optional types refer to
setting digital output variables - index DO index (starting from 0)
- result DO status query result
- type DO type, optional types refer to
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_digital_output(IOType type, int index, BOOL *result);
Get the value of the analog input variable
Get the value of the analog input variable (AI)
- Parameter Description
- type AI type, optional types refer to
setting digital output variables - index AI index (starting from 0)
- result specified AI status query result
- type AI type, optional types refer to
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_analog_input(IOType type, int index, float *result);
Get the value of the analog output variable
Get the value of the analog output variable (AO)
- Parameter Description
- type AO type, optional types refer to
setting digital output variables - index AO index (starting from 0)
- result specified AO status query result
- type AO type, optional types refer to
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_analog_output(IOType type, int index, float *result);
Query whether extended IO is running
Query whether the extended IO module is running
- Parameter Description
- is_running extended IO module running status query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t is_extio_running(BOOL *is_running);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Query extended IO status
int main()
{
BOOL is_running;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
demo.power_on();
//Query TIO status
demo.is_extio_running(&is_running);
std::cout << "tio = " << is_running << std::endl;
return 0;
}
Set the robot arm load
Robot arm payload settings
- Parameter Description
- Payload center of mass and weight data
- Return value ERR_SUCC Success Others indicate failure
errno_t set_payload(const PayLoad *payload);
Get robot arm load data
Get robot arm payload data
- Parameter Description
- Payload query results
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_payload(PayLoad *payload);
Code example:
int example_payload()
{
//Instantiate API object demo
JAKAZuRobot demo;
PayLoad payloadret;
PayLoad payload_set;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Query current payload data
demo.get_payload(&payloadret);
std::cout << " Payload mass is :" << payloadret.mass << " kg" << std::endl;
std::cout << " Payload center of mass is nx: " << payloadret.centroid.x<< " y: " << payloadret.centroid.y << " z: " << payloadret.centroid.z << std::endl;
payload_set.mass = 1.0;
//Unit mm
payload_set.centroid.x = 0; payload_set.centroid.y = 0; payload_set.centroid.z = 10;
//Set current payload data
demo.set_payload(&payload_set);
//Query current payload data
demo.get_payload(&payloadret);
std::cout << " Payload mass is :" << payloadret.mass << " kg" << std::endl;
std::cout << " Payload center of mass is nx: " << payloadret.centroid.x << " y: " << payloadret.centroid.y << " z: " << payloadret.centroid.z << std::endl;
return 0;
}
Set TIOV3 voltage parameters
Set tioV3 voltage parameters
- Parameter Description
- vout_enable Voltage enable, 0: Off, 1: On
- vout_vol Voltage level 0: 24v 1: 12v
- Return value ERR_SUCC Success Others indicate failure
errno_t set_tio_vout_param(int vout_enable, int vout_vol);
Get TIOV3 voltage parameters
Get tioV3 voltage parameters
- Parameter Description
- vout_enable Voltage enable, 0: Off, 1: On
- vout_vol Voltage level 0: 24v 1: 12v
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_tio_vout_param(int* vout_enable, int* vout_vol);
Add or modify TIO semaphore
Add or modify semaphore
- Parameter Description
- sign_info semaphore parameters
- sig_name semaphore name
- chn_id channel ID
- sig_type semaphore type
- sig_addr semaphore address
- value semaphore initial value
- frequency semaphore frequency
- sign_info semaphore parameters
- Return value ERR_SUCC success others fail
errno_t add_tio_rs_signal(SignInfo sign_info);
Code example:
void example_add_tio_rs_signal()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
demo.power_on();
demo.enable_robot();
SignInfo sign_info {0};
memcpy(sign_info.sig_name, "sign_tmp", sizeof("sign_tmp"));
sign_info.chn_id = 0,
sign_info.sig_type = 0,
sign_info.value = 10,
sign_info.frequency = 5;
sign_info.sig_addr = 0x1;
demo.add_tio_rs_signal(sign_info);
demo.disable_robot();
demo.power_off();
demo.login_out();
}
TIO delete semaphore
Delete semaphore
- Parameter Description
- sig_name semaphore name
- Return Value ERR_SUCC Success Others indicate failure
errno_t del_tio_rs_signal(const char* sig_name);
Code example:
void example_del_tio_rs_signal()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
const char* name = "sign_tmp";
demo.del_tio_rs_signal(name);
demo.disable_robot();
demo.power_off();
demo.login_out();
}
TIO RS485 send command
RS485 send command
- Parameter Description
- chn_id Channel number
- data Data field
- Return value ERR_SUCC Success Others indicate failure
errno_t send_tio_rs_command(int chn_id, uint8_t* data,int buffsize);
Code example:
void example_send_tio_rs_command()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
uint8_t cmd[] = {'t', 'e', 's', 't', 'c', 'm', 'd'};
demo.send_tio_rs_command(0, cmd, sizeof(cmd));
demo.disable_robot();
demo.power_off();
demo.login_out();
}
TIO refresh signal information
Refresh signal information
- Parameter Description
- sign_info Signal information array
- sig_name Signal name
- frequency Signal frequency
- sign_info Signal information array
- Return Value ERR_SUCC Success Others indicate failure
errno_t update_tio_rs_signal(SignInfo_simple sign_info);
TIO get semaphore information
Get signal information, it is recommended to first call the above refresh interface before retrieving
- Parameter Description
- sign_info_array Signal information array
- array_len Signal information array length
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_rs485_signal_info(SignInfo* sign_info_array, int* array_len);
Code example:
void example_get_rs485_signal_info()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
SignInfo sign_info[256];
int array_len = 0;
demo.get_rs485_signal_info(sign_info, &array_len);
demo.disable_robot();
demo.power_off();
demo.login_out();
}
Set TIO mode
Set tio mode
- Parameter Description
- pin_type tio type 0 for DI Pins, 1 for DO Pins, 2 for AI Pins
- DI Pins: 0: 0x00 DI2 is NPN, DI1 is NPN. 1: 0x01 DI2 is NPN, DI1 is PNP. 2: 0x10 DI2 is PNP, DI1 is NPN. 3: 0x11 DI2 is PNP, DI1 is PNP.
- DO Pins: High 4 bits of low 8-bit data are DO2 configuration, low 4 bits are DO1 configuration. 0x0 DO is NPN output; 0x1 DO is PNP output; 0x2 DO is push-pull output; 0xF RS485H interface.
- AI Pins: 0: Analog input function enabled, RS485L disabled. 1: RS485L interface enabled, analog input function disabled.
- pin_type tio type 0 for DI Pins, 1 for DO Pins, 2 for AI Pins
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_tio_pin_mode(int pin_type, int pin_mode);
Get TIO mode
Get tio mode
- Parameter Description
- pin_type tio type 0 for DI Pins, 1 for DO Pins, 2 for AI Pins
- DI Pins: 0:0x00 DI2 is NPN, DI1 is NPN, 1:0x01 DI2 is NPN, DI1 is PNP, 2:0x10 DI2 is PNP, DI1 is NPN, 3:0x11 DI2 is PNP, DI1 is PNP
- DO Pins: High 4 bits of low 8-bit data are DO2 configuration, low 4 bits are DO1 configuration. 0x0 DO is NPN output, 0x1 DO is PNP output, 0x2 DO is push-pull output, 0xF RS485H interface
- AI Pins: 0: Analog input function enabled, RS485L disabled, 1: RS485L interface enabled, analog input function disabled
- pin_type tio type 0 for DI Pins, 1 for DO Pins, 2 for AI Pins
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_tio_pin_mode(int pin_type, int* pin_mode);
TIO RS485 communication parameter configuration
RS485 communication parameter configuration
- Parameter Description
- mod_rtu_com When channel mode is set to Modbus RTU, an additional Modbus slave node ID must be specified
- chn_id RS485 channel ID
- slaveId Modbus slave node ID
- baudrate Baud rate
- databit Data bit
- stopbit Stop bit
- parity Parity check
- mod_rtu_com When channel mode is set to Modbus RTU, an additional Modbus slave node ID must be specified
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_rs485_chn_comm(ModRtuComm mod_rtu_com);
TIO RS485 communication parameter query
RS485 communication parameter query
- Parameter Description
- mod_rtu_com is used to receive the obtained channel mode parameters; when querying, chn_id is used as the input parameter
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_rs485_chn_comm(ModRtuComm* mod_rtu_com);
TIO RS485 communication mode configuration
RS485 communication mode configuration
- Parameter Description
- chn_id 0: RS485H, channel 1; 1: RS485L, channel 2
- chn_mode 0: Modbus RTU, 1: Raw RS485, 2: torque sensor
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_rs485_chn_mode(int chn_id, int chn_mode);
TIO RS485 communication mode query
RS485 communication mode query
- Parameter Description
- chn_id input parameter 0: RS485H, channel 1. 1: RS485L, channel 2
- chn_mode output parameter 0: Modbus RTU. 1: Raw RS485. 2: torque sensor
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_rs485_chn_mode(int chn_id, int* chn_mode);
Get Robot Arm Installation Angle
Get installation angle
- Parameter Description
- quat Installation angle quaternion
- appang Installation angle RPY (Roll-Pitch-Yaw) angles
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_installation_angle(Quaternion* quat, Rpy* appang);
Set Robot Arm Installation Angle
Set installation angle
- Parameter Description
- angleX Rotation angle around X-axis
- angleZ Rotation angle around Z-axis
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_installation_angle(double angleX, double angleZ);
Code example:
#include <JAKAZuRobot.h>
#include <iostream>
int main()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
errno_t ret = demo.login_in("192.168.2.194",1,"jaka_sdk","password");
if (ret != ERR_SUCC)
{
std::cerr << "Login failed.";
return -1;
}
ret = demo.set_installation_angle(3.14, 0);
if (ret != ERR_SUCC)
{
std::cerr << "Setting installation angle failed.";
return -1;
}
Quaternion quat;
Rpy rpy;
ret = demo.get_installation_angle(&quat, &rpy);
if (ret != ERR_SUCC)
{
std::cerr << "Getting installation angle failed.";
return -1;
}
std::cout << "quat: [" << quat.x << ", " << quat.y << ", " << quat.z << ", " << quat.s << "]";
std::cout << "anglex: " << rpy.rx << ", anglez: " << rpy.rz << "";
ret = demo.login_out();
if (ret != ERR_SUCC)
{
std::cerr << "Logout failed.";
return -1;
}
return 0;
}
Set system variable
Set system variable
- Parameter Description
- v System variable
- id System variable ID
- value System variable value
- alias System variable name
- v System variable
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_user_var(UserVariable v);
Get Robot Arm Status
Get robot arm status
- Parameter Description
- state Robot arm status query result
- estop 0: Normal, 1: Emergency stop
- poweredOn 0: Not powered, 1: Powered
- servoEnabled 0: Not enabled, 1: Enabled
- state Robot arm status query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_robot_state(RobotState* state);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get robot arm status (emergency stop, powered on, servo enabled)
int example_get_robstate()
{
JAKAZuRobot demo;
//Declare robot arm status structure
RobotState state;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
//Query robot arm status
demo.get_robot_state(&state);
std::cout << "is e_stoped : " << state.estoped << std::endl;
std::cout << "is powered : " << state.poweredOn << std::endl;
std::cout << "is servoEnabled : " << state.servoEnabled << std::endl;
return 0;
}
Get system variable
Get system variable
- Parameter Description
- vlist System variable query result list
- Return value ERR_SUCC Success Others Failure
errno_t get_user_var(UserVariableList* vlist);
Set vibration suppression mode
Set vibration suppression mode
- Parameter description
- mode Vibration suppression mode, 0: Off, 1: Mode 1, 2: Mode 2
- robot_id Robot arm ID, default value is 0
- Return value ERR_SUCC Success Others Failure
errno_t set_vibsuppress_mode(int mode, int robot_id = 0);
The initial default frequency for each model is shown in the table below:
| Load/Model | Default frequency (Hz) |
|---|---|
| MiniCobot1 | 16 |
| MiniCobot2 | 15 |
| 3kg (Zu3 and similar) | 14 |
| 5kg (C5/A5/Dual-arm and similar) | 12 |
| 7kg (Zu7 and similar) | 12 |
| 12kg (Zu12 and similar) | 8 |
| 16kg(Zu16) | 7.5 |
| 18kg(Zu18) | 7.5 |
| 20kg(Zu20) | 7.5 |
| 30kg(Zu30) | 7.4 |
| Max40 | 5 |
Enable vibration suppression settings
Enable vibration suppression settings
- Parameter Description
- frequency Vibration frequency
- damping Vibration damping, default value is 0.05
- robot_id Robot arm ID, default value is 0
- Return value ERR_SUCC Success Others Failure
errno_t vibsuppress_on(double frequency, double damping = 0.05, int robot_id = 0);
Disable vibration suppression settings
Disable vibration suppression settings
- Parameter Description
- robot_id Robot arm ID, default value is 0
- Return value ERR_SUCC Success Others Failure
errno_t vibsuppress_off(int robot_id = 0);
Robot arm safety status settings and queries
Check if the robot arm is in an emergency stop state
Check if the robot arm is in emergency stop state
- Parameter Description
- Emergency stop query result
- Return value ERR_SUCC Success Others Failure
errno_t is_in_estop(BOOL *estop);
Check if the robot arm exceeds the limit
Check if the robot arm exceeds the soft limit
- Parameter Description
- On limit query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t is_on_limit(BOOL *on_limit);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <thread>
//Check if limit exceeded
int example_is_on_limit()
{
JAKAZuRobot demo;
BOOL on_limit;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
demo.power_on();
demo.enable_robot();
while (1)
{
//Check if limit exceeded
demo.is_on_limit(&on_limit);
std::cout << " on_limit is :" << on_limit << std::endl;
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
}
return 0;
}
Query whether the robot arm is in collision protection mode
Check if the robot arm is in collision protection mode
- Parameter Description
- Collision protection state query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t is_in_collision(BOOL *in_collision);
Recover from collision protection mode after collision
Recover from collision protection mode after collision
- Return Value ERR_SUCC Success Others indicate failure
errno_t collision_recover();
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Collision protection status query and recovery
int example_collision_recover()
{
JAKAZuRobot demo;
BOOL in_collision;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
//Check if in collision protection mode
demo.is_in_collision(&in_collision);
std::cout << " in_collision is :" << in_collision << std::endl;
if (in_collision)
//If in collision protection mode, recover from collision protection
{demo.collision_recover();}
else
{std::cout << "robot is not collisio" << std::endl;}
return 0;
}
Set robot arm collision level
Set the robot arm collision level
- Parameter Description
- level Collision level, range [0 to 5], where 0 disables collision, 1 is collision threshold 25N, 2 is collision threshold 50N, 3 is collision threshold 75N, 4 is collision threshold 100N, 5 is collision threshold 125N
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_collision_level(const int level);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//View and set collision level
int example_collision_level()
{
//Instantiate API object demo
JAKAZuRobot demo;
int level;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Query current collision level
demo.get_collision_level(&level);
std::cout << " collision level is :" << level << std::endl;
//Set collision level [0,5], where 0 disables collision, 1 is collision threshold 25N, 2 is collision threshold 50N, 3 is collision threshold 75N, 4 is collision threshold 100N, 5 is collision threshold 125N
demo.set_collision_level(2);
//Query current collision level
demo.get_collision_level(&level);
std::cout << " collision level is :" << level << std::endl;
return 0;
}
Get collision level set by machine
Get the collision level set for the robot arm
- Parameter Description
- level Collision level, range [0 to 5], where 0 disables collision, 1 is collision threshold 25N, 2 is collision threshold 50N, 3 is collision threshold 75N, 4 is collision threshold 100N, 5 is collision threshold 125N
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_collision_level(int *level);
Set robot arm motion type to automatically stop during network exceptions
Set network exception control handle, how long after the SDK loses connection with the robot arm controller will the controller terminate the current motion of the arm
- Parameter description
- millisecond Time parameter, unit: ms, range 500-30000 ms, if set outside this range, the actual effective time will be 2 seconds
- mnt Type of action the robot arm should take when a network exception occurs, optional types: MOT_KEEP (default), MOT_PAUSE, MOT_ABORT
- Return value ERR_SUCC for success, others for failure
errno_t set_network_exception_handle(float millisecond, ProcessType mnt);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Set the motion termination type for the robot arm when a network exception occurs
int example_set_network_exception_handle()
{
float milisec = 100;
errno_t ret;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
//Set torque smoothing conditions
ret = demo.set_network_exception_handle(milisec, MOT_KEEP);
std::cout << ret << std::endl;
return 0;
}
Get the last error code currently occurring on the robot arm
Get the last error code during the operation of the robot arm; when clear_error is called, the last error code will be reset to zero
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_last_error(ErrorCode *code);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//View error code
int example_get_last_errcode()
{
errno_t ret;
//Initialize the storage path for the error code file
JAKAZuRobot demo;
ErrorCode Eret;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
ret = demo.program_load("not_exist999875");//Intentionally load a non-existent program to trigger an error.
std::cout << ret << std::endl;
demo.get_last_error(&Eret);//Query the last error message
std::cout << " error code is :" << Eret.code << " message: "<< Eret.message<< std::endl;
demo.get_last_error(&Eret);//Query the last error message
std::cout << " error code is :" << Eret.code << " message: " << Eret.message << std::endl;
return 0;
}
Error status clear
- Return Value ERR_SUCC Success Others indicate failure
errno_t clear_error();
Register a callback function for robot arm errors
Deprecated interface
Register a callback function for when errors occur on the robot arm
- Parameter Description
- func is a function pointer pointing to a user-defined function
- error_code is the robot arm error code
errno_t set_error_handler(CallBackFuncType func);
Set the storage path for the robot arm error code file
Deprecated interface
Set the error code file path; when the get_last_error interface is used, the error code file path must be set. If get_last_error is not used, there is no need to set this interface
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_errorcode_file_path(char *path);
Use App script program
Run the currently loaded job program
Run the currently loaded job program
- Return Value ERR_SUCC Success Others indicate failure
errno_t program_run();
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include <windows.h>
//Script loading, script run control, script process viewing
int example_program()
{
char name[128];
int cur_line;
JAKAZuRobot demo;
errno_t ret;
ProgramState pstatus;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
if(ret==0){std::cout << "Login successful" << std::endl;}
else{
std::cout << ret << std::endl;
std::cout << "Login failed" << std::endl;}
demo.power_on();
demo.enable_robot();
//Load the example script previously edited via the app
demo.program_load("example");
//Get the name of the loaded program
demo.get_loaded_program(name);
std::cout<<"Pro_name is:"<<name<<std::endl;
//Run the currently loaded program
demo.program_run();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));//Let the program run for 1 second first
//Pause the currently running program
demo.program_pause();
//Get the line number of the currently executing program
demo.get_current_line(&cur_line);
std::cout<<"cur_lineis:"<<cur_line<<std::endl;
//Get the current program state
demo.get_program_state(&pstatus);
std::cout<<"pro_statusis:"<<pstatus<<std::endl;
//Continue running the current program
demo.program_resume();
std::this_thread::sleep_for(std::chrono::milliseconds(10000));//Requires window.h delay 10s
//Terminate the current program
demo.program_abort();
return 0;
}
Pause the currently running job program
Pause the currently running job program
- Return Value ERR_SUCC Success Others indicate failure
errno_t program_pause();
Continue running the currently paused job program
Continue running the currently paused job program
- Return Value ERR_SUCC Success Others indicate failure
errno_t program_resume();
Terminate the currently executing job program
Terminate the currently executing job program
- Return Value ERR_SUCC Success Others indicate failure
errno_t program_abort();
Load the specified job program
Load the specified job program. The program name can be the name in app (to load trajectory reproduction data, the folder name should be prefixed with track/)
- Parameter Description
- file Path to the program file
- Return Value ERR_SUCC Success Others indicate failure
errno_t program_load(const char *file);
Get the name of the loaded job program
Get the name of the loaded job program
- Parameter Description
- file Path to the program file
- size Length of file, maximum is 100
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_loaded_program(char *file, uint8_t size);
Get the execution line number of the current robot arm operation program
Get the execution line number of the current robot arm job program
- Parameter Description
- curr_line Query result of the current line number
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_current_line(int *curr_line);
Get execution status of robot arm job program
Get the execution status of the robot arm job program
- Parameter Description
- status Program execution status query result, PROGRAM_IDLE: stopped status, PROGRAM_RUNNING: running status, PROGRAM_PAUSED: paused status
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_program_state(ProgramState *status);
Get information of robot arm job program
Get robot arm program information
- Parameter Description
- info Program information query result
- logic_line Program script execution line number
- motion_line Motion CMD id being executed
- file Current program file
- program_state Program execution status
- info Program information query result
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_program_info(ProgramInfo *info);
Set robot arm speed multiplier
Set robot arm running rate
- Parameter Description
- rapid_rate is the program running rate, setting range is [0 to 1]
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_rapidrate(double rapid_rate);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include "thread"
//robot arm speed viewing and adjustment
int example_rapidrate()
{
double rapid_rate;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
//Get robot arm motion rate
demo.get_rapidrate(&rapid_rate);
std::cout << "rapid_rate is : " << rapid_rate << std::endl;
//Set robot arm motion rate
demo.set_rapidrate(0.4);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
demo.get_rapidrate(&rapid_rate);
std::cout << "rapid_rate is : " << rapid_rate << std::endl;
return 0;
}
Get robot arm speed multiplier
Get robot arm running rate
- Parameter Description
- rapid_rate Current control system rate
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_rapidrate(double *rapid_rate);
robot arm trajectory reproduction
Set trajectory reproduction configuration parameters
Set trajectory reproduction configuration parameters
- Parameter Description
- para trajectory reproduction configuration parameters
- xyz_interval Coordinate accuracy for trajectory reproduction
- rpy_interval Pose accuracy for trajectory reproduction
- vel Running speed for trajectory reproduction
- acc Running acceleration for trajectory reproduction
- para trajectory reproduction configuration parameters
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_traj_config(const TrajTrackPara *para);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//View and set trajectory reproduction parameters
int example_traj_config()
{
JAKAZuRobot demo;
TrajTrackPara trajpar_read;
TrajTrackPara trajpar_set;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Query current trajectory reproduction parameters
demo.get_traj_config(&trajpar_read);
std::cout << " trajTrackPara is :n xyz interval:" << trajpar_read.xyz_interval << " rpy interval is :" << trajpar_read.rpy_interval << std::endl;
std::cout << " vel: " << trajpar_read.vel << " acc: " << trajpar_read.acc << std::endl;
//Set current trajectory reproduction parameters
trajpar_set.xyz_interval = 0.01; trajpar_set.rpy_interval = 0.01; trajpar_set.vel = 10; trajpar_set.acc = 2;
demo.set_traj_config(&trajpar_set);
//Query current trajectory reproduction parameters
demo.get_traj_config(&trajpar_read);
std::cout << " trajTrackPara is :n xyz interval:" << trajpar_read.xyz_interval << " rpy interval is :" << trajpar_read.rpy_interval << std::endl;
std::cout << " vel: " << trajpar_read.vel << " acc: " << trajpar_read.acc << std::endl;
return 0;
}
Get trajectory reproduction configuration parameters
Get trajectory reproduction configuration parameters
- Parameter Description
- para trajectory reproduction configuration parameters
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_traj_config(TrajTrackPara *para);
Collect trajectory reproduction data control switch
Trajectory reproduction data collection control switch. After turning on this switch, dragging must be started in order to generate a trajectory file.
- Parameter Description
- When mode is TRUE, start data collection; when mode is FALSE, stop data collection
- filename Storage file name for collected data. When filename is a null pointer, the storage file is named with the current date
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_traj_sample_mode(const BOOL mode, char *filename);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#include "thread"
//Trajectory collection switch and status query
int example_traj_sample()
{
BOOL samp_stu;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
char name[20] = "testxx";
//Turn on the trajectory reproduction data collection switch
ret = demo.set_traj_sample_mode(TRUE, name);
//Query the trajectory reproduction collection status
demo.get_traj_sample_status(&samp_stu);
std::this_thread::sleep_for(std::chrono::milliseconds(10000));
demo.set_traj_sample_mode(FALSE, name);
return 0;
}
Query status of collected trajectory reproduction data
Trajectory reproduction data collection status query
- Parameter Description
- When mode is TRUE, data is being collected; when FALSE, data collection has ended. When in data collection status, it is not allowed to turn on the data collection switch again.
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_traj_sample_status(BOOL* sample_status);
Query the file name of trajectory reproduction data already existing in the controller
Deprecated interface
Query the file name of trajectory reproduction data already existing in the controller
- Parameter Description
- filename File name of trajectory reproduction data already existing in the controller
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_exist_traj_file_name(MultStrStorType *filename);
Rename the file name of trajectory reproduction data
Deprecated interface
Rename the file name of trajectory reproduction data
- Parameter Description
- src Original file name
- dest Target file name. File name length cannot exceed 100 characters. File name cannot be empty. Target file name does not support Chinese.
- Return Value ERR_SUCC Success Others indicate failure
errno_t rename_traj_file_name(const char *src,const char *dest);
Delete trajectory reproduction data file from the controller
Deprecated interface
Delete trajectory reproduction data file from the controller
- Parameter Description
- filename File name of the file to delete; file name is the name of the data file
- Return Value ERR_SUCC Success Others indicate failure
errno_t remove_traj_file(const char *filename);
Generate controller execution script from trajectory reproduction data files in the controller
Trajectory replay data file in the controller generates the controller execution script
- Parameter Description
- filename The name of the data file; the filename is the name of the data file without a suffix
- Return Value ERR_SUCC Success Others indicate failure
errno_t generate_traj_exe_file(const char *filename);
Robot arm servo motion mode
Query whether the robot arm is in servo motion state
Query whether the robot arm is in servo motion state
- Parameter Description
- in_servo TRUE means in servo motion state, FALSE means not in servo motion state
- robot_id Robot arm ID, default is 0
- Return value ERR_SUCC Success Others Failure
errno_t is_in_servomove(BOOL *in_servo, int robot_id = 0);
Enable robot arm servo position control mode
Enable robot arm servo position control mode.
- Parameter Description
- enable TRUE means enter servo position control mode, FALSE means exit the mode
- is_block TRUE means blocking mode, FALSE means non-blocking mode, default is blocking mode
- robot_id Robot arm ID, default is 0
- Return Value ERR_SUCC Success Others indicate failure
- Note: In versions v19 and earlier, this interface was a non-blocking command. Starting from v20, this command became a blocking command.
errno_t servo_move_enable(BOOL enable, BOOL is_block = true, int robot_id = 0);
robot arm joint space servo mode motion
Robot arm joint space position control mode
- Parameter Description
- joint_pos Target joint position for robot arm joint motion
- move_mode Robot arm motion mode, optional types are absolute motion (ABS) and incremental motion (INCR)
- Return value ERR_SUCC for success, others indicate failure
errno_t servo_j(const JointValue *joint_pos, MoveMode move_mode);
Code example:
//Robot arm servo joint motion
//When using this interface, you cannot be in edg_servo mode; you can use edg_init(FALSE) to disable it
//When using this interface, you must first call servo_move_enable(TRUE) to enable servo control
//The controller's sending cycle is 8ms; it is recommended that the user's sending cycle is also 8ms. In poor network conditions, the cycle can be appropriately reduced
//Joint speed limit 180 rad/s
//This command is quite different from joint_move: joint_move interpolation is performed by the controller, whereas servo_j requires pre-planned trajectory.
#include <iostream>
#include "JAKAZuRobot.h"
int main()
{
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//TRUE means entering servo mode
demo.servo_move_enable(TRUE);
//Define and initialize the JointValue variable
JointValue joint_pos = {-0.001, 0, 0, 0, 0, -0.001};
for (int i = 0; i < 100; i++)
{
//Joint space servo motion, where INCR represents incremental motion
demo.servo_j(&joint_pos, INCR);
}
//FALSE means exiting servo mode
demo.servo_move_enable(FALSE);
return 0;
}
robot arm joint space servo mode motion extension
robot arm joint space position control mode, with added period adjustability allowing the period to be set as a multiple of 8ms. (In non-blocking servo mode, the controller's queue length must not exceed 100)
- Parameter Description
- joint_pos Target joint position for robot arm joint motion
- move_mode Robot arm motion mode, optional types are absolute motion (ABS) and incremental motion (INCR)
- step_num divides the period, servo_j motion period is step_num*8ms, where step_num >= 1
- queue_num output pointer, returns the current instruction queue length, default is nullptr
- do_info specifies DO information, default is nullptr
- robot_id Robot arm ID, default is 0
- Return value ERR_SUCC for success, others indicate failure
errno_t servo_j(const JointValue *joint_pos, MoveMode move_mode, unsigned int step_num = 1, int *queue_num = nullptr, DOInfo *do_info = nullptr, int robot_id = 0);
robot arm Cartesian space servo mode motion
robot arm Cartesian space position control mode
- Parameter Description
- cartesian_pose target position for robot arm Cartesian space motion
- move_mode Robot arm motion mode, optional types are absolute motion (ABS) and incremental motion (INCR)
- Return Value ERR_SUCC Success Others indicate failure
errno_t servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode);
Code example:
//robot arm servo Cartesian space motion
//When using this interface, you cannot be in edg_servo mode; you can use edg_init(FALSE) to disable it
//When using this interface, you must first call servo_move_enable(TRUE) to enable servo control
//The controller's sending cycle is 8ms; it is recommended that the user's sending cycle is also 8ms. In poor network conditions, the cycle can be appropriately reduced
//Joint speed limit of 180 rad/s; Cartesian space has no intuitive limit, but must comply with this joint speed limit
//This command differs significantly from linear_move; linear_move interpolation is performed by the controller, while servo_p requires prior trajectory planning.
#include <iostream>
#include "JAKAZuRobot.h"
int main()//robot arm servo Cartesian space motion
{
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//TRUE means entering servo mode
demo.servo_move_enable(TRUE);
//Define and initialize the CartesianPose variable
CartesianPose cart;
cart.tran.x = 0; cart.tran.y = 1; cart.tran.z = 0;
cart.rpy.rx = 0; cart.rpy.ry = 0; cart.rpy.rz = 0;
for (int i = 0; i < 100; i++)
{
//Cartesian space servo motion, where INCR represents incremental motion
demo.servo_p(&cart, INCR);
}
//FALSE means exiting servo mode
demo.servo_move_enable(FALSE);
return 0;
}
robot arm Cartesian space servo mode motion extension
robot arm Cartesian space position control mode, with adjustable cycle intervals that can be set to multiples of 8ms (in non-blocking servo mode, the controller queue length must not exceed 100)
- Parameter Description
- cartesian_pose target position for robot arm Cartesian space motion
- move_mode Robot arm motion mode, optional types are absolute motion (ABS) and incremental motion (INCR)
- step_num subdivides the cycle, servo_p motion cycle is step_num*8ms, where step_num>=1
- queue_num output pointer, returns the current instruction queue length, default is nullptr
- do_info specifies DO information, default is nullptr
- robot_id Robot arm ID, default is 0
- Return Value ERR_SUCC Success Others indicate failure
errno_t servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode, unsigned int step_num = 1, int *queue_num = nullptr, DOInfo *do_info = nullptr, int robot_id = 0);
Disable filter in robot arm SERVO mode
Do not use filter in SERVO mode, this command cannot be set in SERVO mode, it can be set after exiting SERVO
- Parameter description
- robot_id Robot arm ID, default is 0
- Return Value ERR_SUCC Success Others indicate failure
errno_t servo_move_use_none_filter(int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Disable filter in servo mode
int example_servo_use_none_filter()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
ret = demo.servo_move_use_none_filter();
std::cout << ret << std::endl;
return 0;
}
First-order low-pass filter in joint space under robot arm SERVO mode
Switch to first-order low-pass filter in joint space under SERVO mode, this command cannot be set in SERVO mode, it can be set after exiting SERVO
- Parameter Description
- cutoffFreq first-order low-pass filter cutoff frequency
- robot_id Robot arm ID, default is 0
errno_t servo_move_use_joint_LPF(double cutoffFreq, int robot_id = 0);
- Parameter Description
- cutoffFreq first-order low-pass filter cutoff frequency
- Return Value ERR_SUCC Success Others indicate failure Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//First-order low-pass filter in joint space under servo mode
int example_servo_use_joint_LPF()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//First-order low-pass filter in joint space under servo mode, cutoff frequency 0.5Hz
ret = demo.servo_move_use_joint_LPF(0.5);
std::cout << ret << std::endl;
return 0;
}
Nonlinear filter in joint space under robot arm SERVO mode
Switch to nonlinear filter in joint space under SERVO mode, this command cannot be set in SERVO mode, it can be set after exiting SERVO
- Parameter Description
- max_vr Maximum limit value (absolute value) of Cartesian space orientation change rate °/s
- max_ar Maximum limit value (absolute value) of acceleration of Cartesian space orientation change rate °/s2
- max_jr Maximum limit value (absolute value) of jerk of Cartesian space orientation change rate °/s3
- robot_id Robot arm ID, default is 0
- Return Value ERR_SUCC Success Others indicate failure
errno_t servo_move_use_joint_NLF(double max_vr, double max_ar, double max_jr, int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Nonlinear filtering of joint space in servo mode
int example_servo_use_joint_NLF()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Nonlinear filtering of joint space in servo mode
ret = demo.servo_move_use_joint_NLF(2,2,4);
std::cout << ret << std::endl;
return 0;
}
Nonlinear filtering of Cartesian space in robot arm SERVO mode
Switch to Cartesian space nonlinear filtering in SERVO mode; this command cannot be set in SERVO mode, it can be set after exiting SERVO
- Parameter Description
- max_vp Maximum limit value (absolute value) of movement command speed in Cartesian space. Unit: mm/s
- max_ap Maximum limit value (absolute value) of movement command acceleration in Cartesian space. Unit: mm/s2
- max_jp Maximum limit value (absolute value) of movement command jerk in Cartesian space Unit: mm/s3
- max_vr Maximum limit value (absolute value) of Cartesian space orientation change rate °/s
- max_ar Maximum limit value (absolute value) of acceleration of Cartesian space orientation change rate °/s2
- max_jr Maximum limit value (absolute value) of jerk of Cartesian space orientation change rate °/s3
- ori_quat Optional parameter that specifies the representation used to describe Cartesian space orientation. 0 means using Euler angles, 1 means using quaternion representation
- robot_id Robot arm ID, default is 0
- Return Value ERR_SUCC Success Others indicate failure
errno_t servo_move_use_carte_NLF(double max_vp, double max_ap, double max_jp, double max_vr, double max_ar, double max_jr, int ori_quat = 0, int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Nonlinear filtering of Cartesian space in servo mode
int example_servo_use_carte_NLF()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Nonlinear filtering of Cartesian space in servo mode
ret = demo.servo_move_use_carte_NLF(2, 2, 4, 2, 2, 4);
std::cout << ret << std::endl;
return 0;
}
Multi-order mean filtering of joint space in robot arm SERVO mode
Switch to joint space multi-order mean filter in SERVO mode; this command cannot be set in SERVO mode, it can be set after exiting SERVO
- Parameter Description
- max_buf Mean filter buffer size
- kp Acceleration filter coefficient
- kv Velocity filter coefficient
- ka position filtering coefficient
- robot_id Robot arm ID, default is 0
- Return Value ERR_SUCC Success Others indicate failure
errno_t servo_move_use_joint_MMF(int max_buf, double kp, double kv, double ka, int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
#define PI 3.14159265358979323846
//Multi-order mean filtering in joint space under servo mode
int example_servo_use_joint_MMF()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Multi-order mean filtering in joint space under servo mode
ret = demo.servo_move_use_joint_MMF(20, 0.2, 0.4, 0.2);
std::cout << ret << std::endl;
return 0;
}
Speed foresight parameter setting in SERVO mode for robot arm
Multi-order mean filter in joint space under SERVO mode; this command cannot be set in SERVO mode, can be set after exiting SERVO
- Parameter Description
- max_buf size of the mean filter buffer
- kp proportional gain; the larger the value, the faster and more precise the response, but prone to jitter; the smaller the value, the smoother and more stable, but with response delay and reduced accuracy.
- ori_quat Optional parameter that specifies the representation used to describe Cartesian space orientation. 0 means using Euler angles, 1 means using quaternion representation
- robot_id Robot arm ID, default is 0
- Return value ERR_SUCC Success Others Failure
errno_t servo_speed_foresight(int max_buf, double kp, int ori_quat = 0, int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Speed foresight parameter setting in servo mode
int example_speed_foresight()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Multi-order mean filtering in joint space under servo mode
ret = demo.servo_speed_foresight(200, 2);
std::cout << ret << std::endl;
return 0;
}
Filter joint space in robot arm SERVO mode
Joint space PCM filter under SERVO mode; this command cannot be set in SERVO mode, can be set after exiting SERVO
- Parameter Description
- max_buf filter buffer size, recommended range [1 to 50]
- kp proportional gain, range from [0.05 to 0.4]; the larger the value, the faster and more precise the response, but prone to jitter; the smaller the value, the smoother and more stable, but with response delay and reduced accuracy
- robot_id Robot arm ID, default is 0
- Return value ERR_SUCC Success Others Failure
errno_t servo_move_use_joint_PCM(int max_buf, double kp, int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Speed foresight parameter setting in servo mode
int example_speed_foresight()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Multi-order mean filtering in joint space under servo mode
ret = demo.servo_move_use_joint_PCM(10, 0.1);
std::cout << ret << std::endl;
return 0;
}
Filter Cartesian space in robot arm SERVO mode
Cartesian space PCM filter under SERVO mode; this command cannot be set in SERVO mode, can be set after exiting SERVO
- Parameter Description
- max_buf filter buffer size, recommended range [1 to 50]
- kp proportional gain, range from [0.05 to 0.4]; the larger the value, the faster and more precise the response, but prone to jitter; the smaller the value, the smoother and more stable, but with response delay and reduced accuracy
- robot_id Robot arm ID, default is 0
- Return value ERR_SUCC Success Others Failure *Note: Compared with joint space PCM filtering, Cartesian space PCM filtering has higher accuracy, but requires higher quality of command points. If the given planning points are of poor quality, it may cause the robot arm to disable itself.
errno_t servo_move_use_carte_PCM(int max_buf, double kp, int robot_id = 0);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Speed foresight parameter setting in servo mode
int example_speed_foresight()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Power on the robot arm
demo.power_on();
//Enable the robot arm
demo.enable_robot();
//Multi-order mean filtering in joint space under servo mode
ret = demo.servo_move_use_carte_PCM(10, 0.1);
std::cout << ret << std::endl;
return 0;
}
robot arm EDG (External Data Guider) function
Currently, this function can only be used through C++ and Python, and it communicates via UDP (User Datagram Protocol)
robot arm EDG enable
Enable robot arm EDG function; it must be enabled before using EDG-related interfaces
- Parameter Description
- en Enable switch, true to activate the EDG function, false to disable this function
- edg_stat_ip SDK client IP address
- edg_port SDK client port number
- edg_mode EDG mode, default value is 0; 0 means all EDG-related interfaces can be called; 1 means all interfaces except edg_servo_j and edg_servo_p can be called
- Return Value ERR_SUCC Success Others indicate failure
- Ps: Once enabled, servo_j and servo_p cannot be called; you must call edg_init(false) to disable the EDG function before calling servo_j and servo_p
errno_t edg_init(BOOL en = true, const char* edg_stat_ip = "0.0.0.0", int edg_port = 10010, int edg_mode = 0);
robot arm high-speed acquisition of EDG feedback data
robot arm high-speed acquisition of EDG feedback data
- Parameter Description
- edg_state EDG feedback data (including joint position, velocity, torque, Cartesian position, and sensor data)
- robot_index Default value is 0, no need to pass a parameter when using the default value
- Return value ERR_SUCC for success, others indicate failure
errno_t edg_get_stat(EDGState *edg_state, unsigned char robot_index = 0);
robot arm acquisition of EDG feedback data issuance timestamp
robot arm acquisition of EDG feedback data issuance timestamp
- Parameter Description
- details Timestamp
- details0 []Seconds
- details1 []Nanoseconds
- details3 []Timestamp count
- details Timestamp
- Return value ERR_SUCC for success, others indicate failure
errno_t edg_stat_details(unsigned long int details[3]);
robot arm EDG joint space servo mode motion
robot arm EDG joint space position control mode
- Parameter Description
- joint_pos Target joint position for robot arm joint motion
- move_mode Robot arm motion mode. Available types: Absolute motion (ABS), incremental motion (INCR), continuous motion (CONTINUE), and stop (STOP)
- step_num Cycle subdivision; edg_servo_j motion cycle = step_num*8ms, where step_num>=1, default value is 1
- robot_index Default value is 0, no need to pass a parameter when using the default value
- Return value ERR_SUCC success others failure
- Ps: Compared to the original servo_j interface, this interface has better real-time control performance,
but requires strictly sending at an 8ms cycle
errno_t edg_servo_j(const JointValue *joint_pos, MoveMode move_mode, unsigned int step_num = 1, unsigned char robot_index = 0);
```
**Code example:**
```c++
#include <iostream>
#include <chrono>
#include <thread>
#include <math.h>
#include "JAKAZuRobot.h"
#define rad2deg(x) ((x)*180.0/M_PI)
#define deg2rad(x) ((x)*M_PI/180.0)
JAKAZuRobot demo;
JointValue jpos = {0, deg2rad(90), deg2rad(-90), deg2rad(90), deg2rad(90), 0};
errno_t ret;
void check_return(int ret, const std::string& func_name) {
if (ret != 0) {
std::cout << func_name << " failed, return value: " << ret << std::endl;
}
}
void edg_servo_j_test() {
const std::chrono::milliseconds interval(8);
for(int i = 0;i<2000;i++)
{
auto start = std::chrono::steady_clock::now();
static JointValue jpos_cmd;
EDGState edgdata;
CartesianPose cpos;
double t = (i - 0)/5000.0;
double kk = 32;
jpos_cmd.jVal[0] = sin(kk*t)*deg2rad(30.0) + jpos.jVal[0];
jpos_cmd.jVal[1] = -sin(kk*t)*deg2rad(20.0) + jpos.jVal[1];
jpos_cmd.jVal[2] = jpos.jVal[2];
jpos_cmd.jVal[3] = -sin(kk*t)*deg2rad(10.0) + jpos.jVal[3];
jpos_cmd.jVal[4] = jpos.jVal[4];
jpos_cmd.jVal[5] = jpos.jVal[5];
ret = demo.edg_servo_j(&jpos_cmd,MoveMode::ABS);
check_return(ret, "edg_servo_j");
ret = demo.edg_get_stat(&edgdata);
check_return(ret, "edg_get_stat");
std::cout << "joint value:" << edgdata.jointVal.jVal[0] << "," << edgdata.jointVal.jVal[1] << "," << edgdata.jointVal.jVal[2]
<< "," << edgdata.jointVal.jVal[3] << "," << edgdata.jointVal.jVal[4] << "," << edgdata.jointVal.jVal[5] << std::endl;
std::cout << "joint velocity:" << edgdata.jointVel.jVel[0] << "," << edgdata.jointVel.jVel[1] << "," << edgdata.jointVel.jVel[2]
<< "," << edgdata.jointVel.jVel[3] << "," << edgdata.jointVel.jVel[4] << "," << edgdata.jointVel.jVel[5] << std::endl;
std::cout << "Joint torque:" << edgdata.jointTorq.jtorq[0] << "," << edgdata.jointTorq.jtorq[1] << "," << edgdata.jointTorq.jtorq[2]
<< "," << edgdata.jointTorq.jtorq[3] << "," << edgdata.jointTorq.jtorq[4] << "," << edgdata.jointTorq.jtorq[5] << std::endl;
std::cout << "Cartesian position:" << edgdata.cartpose.tran.x << "," << edgdata.cartpose.tran.y << "," << edgdata.cartpose.tran.z
<< "," << edgdata.cartpose.rpy.rx << "," << edgdata.cartpose.rpy.ry << "," << edgdata.cartpose.rpy.rz << std::endl;
std::cout << "Sensor:" << edgdata.torqSensor.fx << "," << edgdata.torqSensor.fy << "," << edgdata.torqSensor.fz
<< "," << edgdata.torqSensor.tx << "," << edgdata.torqSensor.ty << "," << edgdata.torqSensor.tz << std::endl;
unsigned long int details[3];
ret = demo.edg_stat_details(details);
check_return(ret, "edg_stat_details");
std::cout << "Details:" << details[0] << "," << details[1] << "," << details[2] << std::endl;
auto end = std::chrono::steady_clock::now();
auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(end - start);
if (elapsed < interval) {
std::this_thread::sleep_for(interval - elapsed);//Wait for the next cycle
}
}
}
int main() {
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
ret = demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
if(ret==0){std::cout << "Login successful" << std::endl;}
demo.power_on();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
demo.enable_robot();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
demo.clear_error();
ret = demo.servo_move_enable(0);
check_return(ret, "servo_move_enable");
ret = demo.edg_init(false);
check_return(ret, "edg_init");
ret = demo.servo_move_use_none_filter();
check_return(ret, "servo_move_use_none_filter");
ret = demo.joint_move(&jpos, ABS, TRUE, 10);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
ret = demo.edg_init(true, "192.168.2.194", 10020, 0);
check_return(ret, "edg_init");
ret = demo.servo_move_enable(1,1); // Must call edg_init first before calling servo_move_enable
check_return(ret, "servo_move_enable");
edg_servo_j_test();
return 0;
}
robot arm EDG Cartesian space servo mode motion
robot arm EDG Cartesian space position control mode
- Parameter Description
- cartesian_pose target position for robot arm Cartesian space motion
- move_mode Robot arm motion mode. Available types: Absolute motion (ABS), incremental motion (INCR), continuous motion (CONTINUE), and stop (STOP)
- step_num multiplied subdivision cycle, edg_servo_p motion cycle is step_num*8ms, where step_num>=1
- robot_index uses the default value, no parameter passing required
- Return Value ERR_SUCC Success Others indicate failure
- Ps: Compared to the original servo_p interface, this interface has better real-time control performance,
but requires strict sending at an 8ms cycle
errno_t edg_servo_p(const CartesianPose *cartesian_pose, MoveMode move_mode, unsigned int step_num = 1, unsigned char robot_index = 0);
Code example:
#include <iostream>
#include <chrono>
#include <thread>
#include <math.h>
#include "JAKAZuRobot.h"
#define rad2deg(x) ((x)*180.0/M_PI)
#define deg2rad(x) ((x)*M_PI/180.0)
JAKAZuRobot demo;
CartesianPose cpos_init;
JointValue jpos = {0, deg2rad(90), deg2rad(-90), deg2rad(90), deg2rad(90), 0};
errno_t ret;
void check_return(int ret, const std::string& func_name) {
if (ret != 0) {
std::cout << func_name << " failed, return value: " << ret << std::endl;
}
}
void edg_servo_p_test() {
const std::chrono::milliseconds interval(8);
for(int i = 0;i<2000;i++)
{
auto start = std::chrono::steady_clock::now();
static CartesianPose cpos_cmd;
double coefficient = sin(i/200.0);
double ori_step = deg2rad(20.0) * coefficient;
double y_step = 100.0 * coefficient;
double x_step = 100.0 * coefficient;
cpos_cmd.tran.x = cpos_init.tran.x + x_step;
cpos_cmd.tran.y = cpos_init.tran.y + y_step;
cpos_cmd.tran.z = cpos_init.tran.z;
cpos_cmd.rpy.rx = cpos_init.rpy.rx + ori_step;
cpos_cmd.rpy.ry = cpos_init.rpy.ry + ori_step;
cpos_cmd.rpy.rz = cpos_init.rpy.rz + ori_step;
ret = demo.edg_servo_p(&cpos_cmd,MoveMode::ABS);
check_return(ret, "edg_servo_p");
auto end = std::chrono::steady_clock::now();
auto elapsed = std::chrono::duration_cast<std::chrono::milliseconds>(end - start);
if (elapsed < interval) {
std::this_thread::sleep_for(interval - elapsed);//Wait for the next cycle
}
}
}
int main() {
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
ret = demo.login_in("192.168.2.194", 1, "jaka_sdk", "password");
if(ret==0){std::cout << "Login successful" << std::endl;}
demo.power_on();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
demo.enable_robot();
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
demo.clear_error();
ret = demo.servo_move_enable(0);
check_return(ret, "servo_move_enable");
ret = demo.edg_init(false);
check_return(ret, "edg_init");
ret = demo.servo_move_use_none_filter();
check_return(ret, "servo_move_use_none_filter");
ret = demo.joint_move(&jpos, ABS, TRUE, 10);
demo.kine_forward(&jpos,&cpos_init);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
ret = demo.edg_init(true, "192.168.2.194", 10020, 0);
check_return(ret, "edg_init");
ret = demo.servo_move_enable(1,1); // Must call edg_init first before calling servo_move_enable
check_return(ret, "servo_move_enable");
edg_servo_p_test();
return 0;
}
robot arm kinematics
robot arm inverse kinematics solution
Calculate the inverse solution for the specified pose under the current tool, current installation angle, and current user coordinate system settings
- Parameter Description
- ref_pos Reference joint space position for inverse solution calculation
- cartesian_pose Cartesian space pose value
- joint_pos Joint space position calculation result when calculation is successful
- Return Value ERR_SUCC Success Others indicate failure
errno_t kine_inverse(const JointValue *ref_pos, const CartesianPose *cartesian_pose, JointValue *joint_pos);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
// robot arm inverse solution Given tcp_pos, find joint_pos
int example_kine_inverse()
{
errno_t ret;
JAKAZuRobot demo;
//Initialize reference point
JointValue ref_jpos = { 2*PI/180, 90*PI/180, 90*PI/180 , 90*PI/180, -90*PI/180, 0*PI/180 };
//Initialize Cartesian space point coordinates
CartesianPose tcp_pos;
tcp_pos.tran.x = -350; tcp_pos.tran.y = 100; tcp_pos.tran.z = 300;
tcp_pos.rpy.rx = -180*PI/180; tcp_pos.rpy.ry = 0; tcp_pos.rpy.rz = 90*PI/180;
//Initialize return value
JointValue joint_pos = { 0,0,0,0,0,0 }; ;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Calculate inverse solution
ret = demo.kine_inverse(&ref_jpos, &tcp_pos, &joint_pos);
std::cout << ret << std::endl;
for (int i = 0; i < 6; i++)
{
std::cout << "joint [" << i + 1 << "] is :" << joint_pos.jVal[i]*180/PI << std::endl;
}
return 0;
}
robot arm inverse solution extension
Calculate the inverse solution for the specified pose under the specified tool, current installation angle, and specified user coordinate system settings
- Parameter Description
- ref_pos Reference joint space position for inverse solution calculation
- cartesian_pose Cartesian space pose value
- joint_pos Joint space position calculation result when calculation is successful
- tool Specified tool coordinate system; if not specified, use the current default tool coordinate system
- userFrame Specified user coordinate system; if not specified, use the current default user coordinate system
- Return Value ERR_SUCC Success Others indicate failure
errno_t kine_inverse(const JointValue *ref_pos, const CartesianPose *cartesian_pose, JointValue *joint_pos, const CartesianPose* tool, const CartesianPose* userFrame);
robot arm forward kinematics solution
Calculate the pose value for the specified joint position under the current tool, current installation angle, and current user coordinate system settings
- Parameter Description
- joint_pos Joint space position
- cartesian_pose Cartesian space pose calculation result
- Return Value ERR_SUCC Success Others indicate failure
errno_t kine_forward(const JointValue *joint_pos, CartesianPose *cartesian_pose);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
// 4.55 robot arm forward kinematics Given joint_pos, find tcp_pos
int example_kine_forward()
{
errno_t ret;
JAKAZuRobot demo;
//Initialize return value
CartesianPose tcp_pos;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Initialize joint matrix
JointValue joint_pos = { 0.558, 0.872, 0.872 , 0.349, 0.191, 0.191 };
//Calculate forward kinematics
ret = demo.kine_forward(&joint_pos, &tcp_pos);
std::cout << ret << std::endl;
std::cout << "tcp_pos is:\n x: " << tcp_pos.tran.x << " y: " << tcp_pos.tran.y << " z: " << tcp_pos.tran.z << std::endl;
std::cout << "rx: " << tcp_pos.rpy.rx << " ry: " << tcp_pos.rpy.ry << " rz: " << tcp_pos.rpy.rz << std::endl;
return 0;
}
Extended robot arm forward kinematics calculation
Calculate the pose value of the specified joint position under the specified tool, current installation angle, and specified user coordinate system settings
- Parameter Description
- joint_pos Joint space position
- cartesian_pose Cartesian space pose calculation result
- tool Specified tool coordinate system; if not specified, use the current default tool coordinate system
- userFrame Specified user coordinate system; if not specified, use the current default user coordinate system
- Return Value ERR_SUCC Success Others indicate failure
errno_t kine_forward(const JointValue *joint_pos, CartesianPose *cartesian_pose, const CartesianPose* tool, const CartesianPose* userFrame);
Convert Euler angles to rotation matrix
Conversion from Euler angles to rotation matrix
- Parameter Description
- rpy Euler angle data to be converted
- rot_matrix Converted rotation matrix
- Return Value ERR_SUCC Success Others indicate failure
errno_t rpy_to_rot_matrix(const Rpy *rpy, RotMatrix *rot_matrix);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
// 4.56 Euler angles to rotation matrix
int example_rpy_to_rot_matrix()
{
errno_t ret;
JAKAZuRobot demo;
//Initialize rotation matrix
Rpy rpy;
rpy.rx = -1.81826; rpy.ry = -0.834253; rpy.rz = -2.30243;
//Initialize return value
RotMatrix rot_matrix;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
//Convert Euler angles to rotation matrix
ret = demo.rpy_to_rot_matrix(&rpy, &rot_matrix);
std::cout << ret << "eul2rotm" << std::endl;
std::cout << rot_matrix.x.x << " " << rot_matrix.y.x << " " << rot_matrix.z.x << std::endl;
std::cout << rot_matrix.x.y << " " << rot_matrix.y.y << " " << rot_matrix.z.y << std::endl;
std::cout << rot_matrix.x.z << " " << rot_matrix.y.z << " " << rot_matrix.z.z << std::endl;
return 0;
}
Convert rotation matrix to Euler angles
Conversion from rotation matrix to Euler angles
- Parameter Description
- rot_matrix Rotation matrix data to be converted
- rpy Converted RPY Euler angle result
- Return Value ERR_SUCC Success Others indicate failure
errno_t rot_matrix_to_rpy(const RotMatrix *rot_matrix, Rpy *rpy);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
// 4.57 Rotation matrix ---> Euler angles
int example_rot_matrix_to_rpy()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Initialize Euler angles
Rpy rpy;
//Initialize rotation matrix
RotMatrix rot_matrix;
rot_matrix.x.x = -0.4488, rot_matrix.y.x = -0.4998, rot_matrix.z.x = 0.7408;
rot_matrix.x.y = -0.6621, rot_matrix.y.y = -0.3708, rot_matrix.z.y = -0.6513;
rot_matrix.x.z = 0.6002, rot_matrix.y.z = -0.7828, rot_matrix.z.z = -0.1645;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
ret = demo.rot_matrix_to_rpy(&rot_matrix, &rpy);
std::cout << ret << "rotm2eul:" << std::endl;
std::cout << rpy.rx << " " << rpy.ry << " " << rpy.rz << std::endl;
return 0;
}
Convert quaternion to rotation matrix
Conversion from quaternion to rotation matrix
errno_t quaternion_to_rot_matrix(const Quaternion *quaternion, RotMatrix *rot_matrix);
- Parameter Description
- quaternion Quaternion data to be converted
- rot_matrix Converted rotation matrix result
- Return Value ERR_SUCC Success Others indicate failure Code example:
#include <iostream>
#include "JAKAZuRobot.h"
// 4.58 Quaternion --> rotation matrix
int example_quaternion_to_rot_matrix()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Initialize quaternion
Quaternion quat;
quat.s = 0.0629; quat.x = 0.522886; quat.y = -0.5592; quat.z = 0.6453;
//Initialize rotation matrix
RotMatrix rot_matrix;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
ret = demo.quaternion_to_rot_matrix(&quat, &rot_matrix);
std::cout << ret << "quatl2rotm:" << std::endl;
std::cout << rot_matrix.x.x << " " << rot_matrix.y.x << " " << rot_matrix.z.x << std::endl;
std::cout << rot_matrix.x.y << " " << rot_matrix.y.y << " " << rot_matrix.z.y << std::endl;
std::cout << rot_matrix.x.z << " " << rot_matrix.y.z << " " << rot_matrix.z.z << std::endl;
return 0;
}
Get the DH parameters of the currently connected robot arm
Get robot arm DH parameters
- Parameter Description
- dhParam DH parameters: alpha, a, d, theta
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_dh_param(DHParam* dh_param);
Convert rotation matrix to quaternion
Conversion from rotation matrix to quaternion
- Parameter Description
- rot_matrix Rotation matrix to be converted
- quaternion Resulting converted quaternion
- Return Value ERR_SUCC Success Others indicate failure
errno_t rot_matrix_to_quaternion(const RotMatrix *rot_matrix, Quaternion *quaternion);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
// 4.59 rotation matrix ---> quaternion
int example_rot_matrix_to_quaternion()
{
errno_t ret;
//Instantiate API object demo
JAKAZuRobot demo;
//Initialize quaternion
Quaternion quat;
//Initialize rotation matrix
RotMatrix rot_matrix;
rot_matrix.x.x = -0.4488774, rot_matrix.y.x = -0.499824, rot_matrix.z.x = 0.740795;
rot_matrix.x.y = -0.662098, rot_matrix.y.y = -0.370777, rot_matrix.z.y = -0.651268;
rot_matrix.x.z = 0.600190, rot_matrix.y.z = -0.782751, rot_matrix.z.z = -0.164538;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
ret = demo.rot_matrix_to_quaternion(&rot_matrix, &quat);
std::cout << ret << "rotm2quat:" << std::endl;
printf("%lf %lf %lf %lf \n", quat.s, quat.x, quat.y, quat.z);
return 0;
}
robot arm force control interface
The JAKA robot arm provides a set of force control interfaces based on the end force sensor, allowing users to perform advanced force control functions such as constant force compliance control, thereby enabling more complex application scenarios like specifying a dragging direction in Cartesian space, force-controlled assembly, polishing, and so on.
It should be noted that these interfaces rely on the end force sensor.
It is recommended to read this section after completing the Force Control product user manual, and to refer to the JAKA SDK Force Control Function Quick Start Guide for better understanding. To avoid lengthy text, in this section “force control” represents “force compliance control,” and “end force sensor,” “force sensor,” and “sensor” all refer to a 6-dimensional or 1-dimensional force/torque sensor mounted at the end of the robot arm.
Set end force sensor model
Set end force sensor model
- Parameter Description
- sensor_brand Sensor model, value range is 1-6 or 10, which must match the model number engraved on the sensor's hardware casing. Among them, 10 specifically refers to the sensor already built into the inside of the robot arm flange. This type of sensor is automatically managed by the system and does not require calling this interface for configuration.
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_torsenosr_brand(int sensor_brand);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Set the end force sensor model
int example_set_torsensor_brand()
{
errno_t ret;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
//Set the end force sensor model
ret = demo.set_torsenosr_brand(2);
std::cout << ret << std::endl;
return 0;
}
Get end force sensor model
Get end force sensor model
- Parameter Description
- sensor_brand Sensor model,
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_torsenosr_brand(int* sensor_brand);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Get the end force sensor model
int example_get_torsensor_brand()
{
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
errno_t ret;
int cur_sensor;
//Get the end force sensor model
ret = demo.get_torsenosr_brand(&cur_sensor);
std::cout << ret << std::endl;
std::cout << "The end sensor model is: " << cur_sensor << std::endl;
return 0;
}
Enable or disable end force sensor
Enable or disable end force sensor
- Parameter Description
- sensor_mode 0 means turning off the sensor, 1 means turning on the sensor
- Return Value ERR_SUCC Success Others indicate failure
- Note: For robot arm models with sensors already built into the end flange (such as the S series), the sensors are turned on by default, and generally there is no need to call this interface unless there are special requirements.
errno_t set_torque_sensor_mode(int sensor_mode);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Turn on or off the end force sensor
int example_set_torque_sensor_mode()
{
errno_t ret;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
demo.servo_move_enable(TRUE);
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
//Turn on or off the end force sensor, 1 on, 0 off
ret = demo.set_torque_sensor_mode(1);
std::cout << ret << std::endl;
return 0;
}
Set sensor end load
Set the end sensor load
Note: Please carefully distinguish between set_torq_sensor_tool_payload and set_payload.
payload affects the dynamics of the robot arm;
tool_payload affects the force control effect (i.e., force and torque compensation during force control)
Note: For robot arm models with built-in sensors in the end flange (such as the S series), the sensor’s end load is no different from the robot arm’s load. In this case, the two corresponding setting and query interfaces are equivalent.
- Parameter Description
- payload end load, unit: kg, mm
- Return value ERR_SUCC Success Others indicate failure
errno_t set_torq_sensor_tool_payload(const PayLoad* payload);
Get sensor end load
Get the sensor’s end load
- Parameter Description
- payload end load, unit: kg, mm
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_torq_sensor_tool_payload(PayLoad *payload);
Code example:
#include <iostream>
#include "JAKAZuRobot.h"
//Identify sensor load and get load identification status, set and get the sensor’s end load
int example_sensor_payload()
{
JointValue joint_pos;
PayLoad pl,pl_ret;
errno_t ret;
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
demo.power_on();
demo.enable_robot();
//The end position must be set according to actual conditions; this is only an example, please do not use directly
joint_pos.jVal[0] = 0;
joint_pos.jVal[1] = 0;
joint_pos.jVal[2] = 0;
joint_pos.jVal[3] = 0;
joint_pos.jVal[4] = 0;
joint_pos.jVal[5] = 0;
//Start identifying sensor load
ret = demo.start_torq_sensor_payload_identify(&joint_pos);
do
{
std::this_thread::sleep_for(std::chrono::milliseconds(1000));
//Query sensor load status
demo.get_torq_sensor_identify_staus(&ret);
std::cout << ret << std::endl;
} while (1 == ret);
//Get identification result
if(ret == 0) ret = demo.get_torq_sensor_payload_identify_result(&pl);
std::cout << ret << std::endl;
//Set the sensor’s end payload
ret = demo.set_torq_sensor_tool_payload(&pl);
//Get the currently set sensor end payload
ret = demo.get_torq_sensor_tool_payload(&pl_ret);
return 0;
}
Get sensor end load identification status
Get sensor end load identification status
- Parameter Description
- identify_status 0 means identification is complete and results are ready to be read, 1 means there are no results available to read, 2 means identification failed.
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_torq_sensor_identify_staus(int *identify_status);
Start identifying sensor end load
Start identifying sensor end load Note: This is a command that will trigger movement, causing the robot arm to move to the position specified by jointposition. The identification process may take 1–3 minutes.
- Parameter Description
- joint_pos Payload identification endpoint. For notes on endpoint position settings, please refer to the relevant function description in the Force Control product user manual.
- Return Value ERR_SUCC Success Others indicate failure
errno_t start_torq_sensor_payload_identify(const JointValue *joint_pos);
Get sensor end load identification result
Get sensor end load identification result
- Parameter Description
- payload End payload, unit: kg, mm
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_torq_sensor_payload_identify_result(PayLoad *payload);
Set end force sensor communication parameters
Deprecated interface
Set end force sensor communication parameters
- Parameter Description
- type: 0 for using Ethernet or USB, 1 for using TIO.
- ip_addr is the sensor IP address when using Ethernet.
- port is the force control sensor port number when using Ethernet.
- When set to 1 or using USB, ip_addr and port are not applicable. Just use the default parameters as shown in the example.
- Return Value ERR_SUCC Success Others indicate failure
- For robot models with built-in sensors in the end flange (such as the S series), the system has already automatically assigned them, and no configuration is required.
errno_t set_torque_sensor_comm(const int type, const char *ip_addr, const int port);
Get end force sensor communication parameters
Deprecated interface
Get end force sensor communication parameters
- Parameter Description
- type: 0 for using Ethernet or USB, 1 for using TIO.
- ip_addr is the sensor IP address when using Ethernet.
- port is the force control sensor port number when using Ethernet.
- When using TIO or USB, ip_addr and port are invalid parameters, and the return value has no actual meaning.
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_torque_sensor_comm(int *type, char *ip_addr, int *port);
Disable force compliance control
Deprecated interface
Disable force compliance control (effective for constant force compliance control and speed compliance control, but not effective for tool dragging)
- Return Value ERR_SUCC Success Others indicate failure
errno_t disable_force_control();
Set end force sensor low-pass filter cutoff frequency
Set end force sensor low-pass filter cutoff frequency
- Parameter Description
- torque_sensor_filter Low-pass filter cutoff frequency, unit: Hz
errno_t set_torque_sensor_filter(const float torque_sensor_filter);
Get end force sensor low-pass filter cutoff frequency
Get end force sensor low-pass filter cutoff frequency
- Parameter Description
- torque_sensor_filter Low-pass filter cutoff frequency, unit: Hz
errno_t get_torque_sensor_filter(float *torque_sensor_filter);
Set end force sensor soft limit
Set end force sensor soft limit
- Parameter Description
- torque_sensor_soft_limit Maximum allowable force or torque value in each direction, exceeding this value will trigger collision protection. Force limit: fx, fy, fz Units: N; Torque limit tx, ty, tz Units: Nm
errno_t set_torque_sensor_soft_limit(const FTxyz torque_sensor_soft_limit);
Get end force sensor soft limit
Get end force sensor soft limit
- Parameter Description
- torque_sensor_soft_limit Maximum allowable force or torque value in each direction, exceeding this value will trigger collision protection. Force limit: fx, fy, fz Units: N; Torque limit tx, ty, tz Units: Nm
errno_t get_torque_sensor_soft_limit(FTxyz *torque_sensor_soft_limit);
Enable or disable tool drag
Deprecated interface
To enable or disable tool dragging, the sensor must be turned on and appropriate compliance control parameters set. In addition, it is recommended to perform at least one sensor zero calibration before enabling tool dragging.
- Parameter Description
- enable_flag 0 disables tool dragging, 1 enables it
- Return Value ERR_SUCC Success Others indicate failure
errno_t enable_admittance_ctrl(const int enable_flag);
Set force control type and zero calibration (initialization) options
Deprecated interface
Set force control type and zero calibration (initialization) options
- Parameter Description
- sensor_compensation: 1 means immediately perform a sensor zero calibration, and switch APP's real-time force curve display and torq_sensor_monitor_data.actTorque to actual external force; 0 means no zero calibration, and when not in force control state, switch APP's real-time force curve display and torq_sensor_monitor_data.actTorque to sensor's raw readings (if in force control state it still displays actual external force).
- compliance_type: 0 means no compliance control method is used, 1 means constant force compliance control is enabled, 2 means speed compliance control is enabled.
- Return Value ERR_SUCC Success Others indicate failure
errno_t set_compliant_type(int sensor_compensation, int compliance_type);
Get force control type and reading display (initialization) status
Deprecated interface
Get force control type and sensor initialization status
- Parameter Description
- sensor_compensation indicates whether sensor compensation is enabled; 1 means APP's real-time force curve display and torq_sensor_monitor_data.actTorque show actual external force; 0 means when not in force control state APP's real-time force curve display and torq_sensor_monitor_data.actTorque show sensor's raw readings (if in force control state it still shows actual external force).
- compliance_type 0 means no compliance control method is used; 1 means constant force compliance control; 2 means speed compliance control
- Return Value ERR_SUCC Success Others indicate failure
errno_t get_compliant_type(int *sensor_compensation, int *compliance_type);
Set force compliance control parameters
Deprecated interface
Set force compliance control parameters
- Parameter Description
- axis: 0, x-axis; 1, y-axis; 2, z-axis; 3, rx; 4, ry; 5, rz.
- opt: 0 off, 1 on.
- ftUser: damping, affects the stiffness the robot’s end shows to the external environment. The larger this parameter is, the greater the stiffness displayed by the robot’s end. Units are ×8 N·s/m (for x/y/z), ×16 Nm·s/(π·rad) (for rx/ry/rz)
- ftReboundFK: rebound, indicates the elasticity coefficient between the robot’s compliance control process and the commanded trajectory (or initial position), units N/mm (for x/y/z), Nm/rad (for rx/ry/rz).
- ftConstant: represents target force, units N (for x/y/z), Nm (for rx/ry/rz).
- ftNnormalTrack: historical compatibility interface, currently must be set to 0 in all cases to ensure normal operation.
- For understanding the above parameters, please refer to the relevant explanations in the 171 Force Control Product User Manual.
- Return value ERR_SUCC Success Others indicate failure
errno_t set_admit_ctrl_config(int axis, int opt, double ftUser, double ftConstant, int ftNnormalTrack, double ftReboundFK);
Get force compliance control parameters
Deprecated interface
Get force compliance control parameters
- Parameter Description
- admit_ctrl_cfg is the storage address of the robot arm's force compliance control parameters, an array of 6 AdmitCtrlType elements corresponding to force compliance control parameters in the x, y, z, rx, ry, rz directions
- Return value ERR_SUCC Success Others Failure
errno_t get_admit_ctrl_config(RobotAdmitCtrl *admit_ctrl_cfg);
Set speed compliance control parameters
Deprecated interface
Set speed compliance control parameters
- Parameter description
- vel_cfg is the speed compliance control parameters
- Return value ERR_SUCC for success, others for failure
errno_t set_vel_compliant_ctrl(const VelCom *vel_cfg);
Set compliant control force condition
Deprecated interface
Set compliant control force condition
- Parameter description
- ft is the compliant control torque limit; exceeding the limit value will slow down until stopping
- Return value ERR_SUCC for success, others for failure
errno_t set_compliance_condition(const FTxyz *ft);
Sensor zero calibration
Deprecated interface
Trigger sensor zero calibration and block for 0.5 seconds.
errno_t zero_end_sensor();
Sensor hardware-level calibration
Deprecated interface
Trigger sensor hardware-level calibration to improve sensor reading accuracy.
- Parameter description
- type: 0: no action. 1: perform calibration. 2: query current calibration values.
- Note: This command will not take effect immediately, but will perform calibration at the first power-on after restarting the robot control cabinet, using the current state of the sensor. The calibration process may take 5-10 seconds, so after issuing this command, wait 5-10 seconds at the next restart and power-on before enabling to ensure the best calibration result.
- Note: This command should only be used when extreme improvement of sensor reading accuracy is required. Incorrect use may cause excessive deviation of the sensor zero point, leading to unexpected situations. It is not recommended to calibrate frequently or repeatedly. General sensor reading calibration is recommended via the sensor zero-calibration software interface.
- Note: After this command takes effect, be sure to record the current calibration result displayed on the APP at startup, and ensure that the actual force applied during subsequent use combined with this calibration result does not exceed the sensor's measurement range.
errno_t tio_sensor_calib(int type);
Get sensor operating status
Get sensor operating status
- Parameter description
- sensor_mode: Sensor on or off state, 0 is off; 1 is on
errno_t get_torque_sensor_mode(int* sensor_mode);
Get sensor status and data
Get sensor operating status
- Parameter description
- type: Type of data acquisition, 1: same as torq_sensor_monitor_data.actTorque; 2: same as torq_sensor_monitor_data.torque, the sensor's raw reading; 3: same as torq_sensor_monitor_data.realTorque, actual force after subtracting load gravity compensation and sensor offset;
- TorqSensorData: Structure containing sensor status, error codes, and readings
- Note: type with value 1 is a compatibility interface for version 1.7.1 and below. In version 1.7.2 and above, values obtained for parameters 1 and 3 are the same, but using 3 is recommended.
errno_t get_torque_sensor_data(int type, TorqSensorData* data);
Set constant-force compliance control parameters
Set constant-force compliance control parameters
- Parameter description
- axis: 0, x-axis; 1, y-axis; 2, z-axis; 3, rx; 4, ry; 5, rz.
- opt: 0 off, 1 on.
- ftUser: Damping, affects the stiffness that the robot arm's end exhibits toward the external environment. The larger this parameter, the greater the stiffness displayed at the end of the robot arm. Units are ×8 N·s/m (for x/y/z), ×16 Nm·s/(π·rad) (for rx/ry/rz)
- ftReboundFK: Rebound, represents the elastic coefficient between the robot arm's compliant control and the commanded trajectory (or initial position), with units of N/mm (for x/y/z) and Nm/rad (for rx/ry/rz).
- ftConstant: represents target force, units N (for x/y/z), Nm (for rx/ry/rz).
- For understanding the above parameters, please further refer to the relevant descriptions in the 172APP Programming Instruction Help section of the 172APP User Manual.
- Return value ERR_SUCC Success Other Failure
errno_t set_ft_ctrl_config(AdmitCtrlType admit_ctrl_cfg);
Get constant-force compliance control parameters
Get constant-force compliance control parameters
- Parameter description
- cfg Storage address for the robot arm force control compliance parameters, an array of 6 AdmitCtrlType, corresponding to the force compliance control parameters for the x, y, z, rx, ry, and rz directions.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_ctrl_config(RobotAdmitCtrl* cfg);
Set constant-force compliance control coordinate system
Set constant-force compliance control coordinate system
- Parameter description
- ftFrame 0: The directional axis of the force control coordinate system will remain parallel to the currently active tool coordinate system in real time; 1: The directional axis of the force control coordinate system will remain parallel to the currently active user coordinate system in real time.
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_ctrl_frame(FTFrameType ftFrame);
Get constant-force compliance control coordinate system
Obtain the constant force compliance control coordinate system, calling the controller's internal new interface.
- Parameter description
- ftFrame 0: The directional axis of the force control coordinate system will remain parallel to the currently active tool coordinate system in real time; 1: The directional axis of the force control coordinate system will remain parallel to the currently active user coordinate system in real time.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_ctrl_frame(FTFrameType* ftFrame);
Set force control drag feel parameters
Set the force control drag feel parameters, calling the corresponding internal interface of the controller.
- Parameter description
- cfg Configuration for the tool drag.
- For understanding the above parameters, please further refer to the relevant descriptions in the 172APP User Manual and the 172 Force Control Product User Manual.
- Return value ERR_SUCC for success, others for failure
errno_t set_tool_drive_config(ToolDriveConfig cfg);
Get tool dragging parameters
Obtain the tool drag parameters, calling the controller's internal new interface.
- Parameter description
- cfg Storage address for the robot arm force control compliance parameters, an array of 6 AdmitCtrlType, corresponding to the force compliance control parameters for the x, y, z, rx, ry, and rz directions.
- Return value ERR_SUCC for success, others for failure
errno_t get_tool_drive_config(RobotToolDriveCtrl* cfg);
Enable tool dragging
To enable or disable tool dragging, the sensor must be turned on and appropriate compliance control parameters set. In addition, it is recommended to perform at least one sensor zero calibration before enabling tool dragging.
- Parameter description
- enable_flag 0 disables tool drag, 1 enables it.
- Return value ERR_SUCC for success, others for failure
errno_t enable_tool_drive(const int enable_flag);
Activate/Deactivate Constant Force Compliant Control
Activate/Deactivate Constant Force Compliant Control
- Parameter description
- enable_flag 0 disables, 1 enables; you need to enable the sensor and set appropriate compliance control parameters. In addition, it is recommended to perform at least one force control sensor zero calibration before enabling constant force compliance control.
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_ctrl_mode(BOOL enable);
Set force control termination condition
Set the force control stop conditions; the meaning is the same as the command of the same name in APP graphical programming. Please refer to the relevant descriptions in the 172APP Programming Instruction Help section of the 172APP User Manual.
- Parameter description
- condition: An array of 6-dimensional ForceStopCondition:
- axis Direction, 0-5 correspond to x, y, z, rx, ry, rz respectively.
- opt Whether to enable force control stop conditions, 0 means unchecked, non-zero value means checked.
- lower_limit_opt 0 means no lower limit is set, non-zero value means limit is set
- lower_limit lower limit value
- upper_limit_opt 0 means no upper limit is set, non-zero value means limit is set
- upper_limit upper limit value
- condition: An array of 6-dimensional ForceStopCondition:
- Return value ERR_SUCC for success, others for failure
errno_t set_force_stop_condition(ForceStopConditionList condition);
Get constant-force compliance enable status
Get constant-force compliance enable status
- Parameter description
- enable, 0 means disabled, 1 means enabled, 2 means speed mode (speed mode is no longer supported in controller versions 1.7.2 and above, 2 will only appear in compatibility code)
errno_t get_ft_ctrl_mode(BOOL* enable);
Set approach speed limit
Set approach speed limit
- Parameter description
- vel linear speed limit, mm/s
- angularVel angular speed limit, rad/s
- For the specific meaning of this setting, please refer to the relevant description in the 172APP user manual.
errno_t set_approach_speed_limit(double vel, double angularVel);
Get approach speed limit
Get approach speed limit
- Parameter description
- speed_limit linear speed limit, mm/s
- Parameter description angular_speed_limit angular speed limit, rad/s
errno_t get_approach_speed_limit(double *vel, double *angularVel);
Set constant-force control tolerance
Set constant-force control tolerance
- Parameter description
- force force tolerance, N
- torque torque tolerance, Nm
errno_t set_ft_tolerance(double force, double torque);
Get constant-force control tolerance
Set constant-force control tolerance
- Parameter description
- force force tolerance, N
- torque torque tolerance, Nm
errno_t get_ft_tolerance(double *force, double *torque);
Get tool dragging enable status
Obtain the force control tool drag enable status
- Parameter description
- enable: 0 means off, 1 means on
- state: whether current drag state has motion restriction warning; 0 means no warning, others mean warning triggered. After converting to binary, the valid bits are 16 bits. From low to high bits, the warning trigger types are in order: singularity trigger for points 1-6, joint soft limit trigger for joints 1-9, speed restriction trigger
- Return value ERR_SUCC success, others failure
errno_t get_tool_drive_state(int *enable, int *state);
Note:
State return value is only supported for S series robot arms, meaningless for other models. For S series configuration, singularity points 1-3 are elbow singularity, wrist singularity, shoulder singularity; singularity points 4-6 and joint flags 7-9 are meaningless.
Get tool drag coordinate system
Get tool drag coordinate system.
- Parameter description
- toolDragFrame 0: The directional axis of the drag coordinate system will remain parallel in real-time to the currently active tool coordinate system; 1: The directional axis of the drag coordinate system will remain parallel in real-time to the currently active user coordinate system
- Return value ERR_SUCC Success Other failures
errno_t get_tool_drive_frame(FTFrameType *ftFrame);
Set tool drag coordinate system
Set the tool drag coordinate system.
- Parameter description
- toolDragFrame 0: The directional axis of the drag coordinate system will remain parallel in real-time to the currently active tool coordinate system; 1: The directional axis of the drag coordinate system will remain parallel in real-time to the currently active user coordinate system
- Return value ERR_SUCC
errno_t set_tool_drive_frame(FTFrameType ftFrame);
Note:
The following interfaces related to fusion drag, motion limit (singularity and joint limit) warning range are only used for S series robot arms. For detailed meaning of these settings, please refer to the relevant instructions in the APP user manual.
Get fusion drag sensitivity
Get the fusion drag sensitivity.
- Parameter description
- level Sensitivity level, 0-5, 0 means off, the smaller the value, the less sensitive
errno_t get_fusion_drive_sensitivity_level(int *level);
Set fusion drag sensitivity
Set the fusion drag sensitivity.
- Parameter description
- level Sensitivity level, 0-5, 0 means off, the smaller the value, the less sensitive
- For detailed meaning of this setting, please refer to the relevant instructions in the APP user manual.
errno_t set_fusion_drive_sensitivity_level(int level);
Get motion restriction (singularity and joint limit) warning range
Get the motion limit (singularity and joint limit) warning range.
- Parameter description
- warningRange Range level, 1-5, the smaller the value, the larger the warning range
errno_t get_motion_limit_warning_range(int *warningRange);
Set motion restriction (singularity and joint limit) warning range
Set the motion limit (singularity and joint limit) warning range.
- Parameter description
- warningRange Range level, 1-5, the smaller the value, the larger the warning range
- For detailed meaning of this setting, please refer to the relevant instructions in the APP user manual.
errno_t set_motion_limit_warning_range(int warningRange);
Get force control speed limit
Get compliant speed limit.
errno_t get_compliant_speed_limit(double *vel, double *angularVel);
Set force control speed limit
Set compliant speed limit.
- Parameter description
- speed_limit linear speed limit, mm/s
- angular_speed_limit Angular velocity limit, rad/s
- For detailed meaning of this setting, please refer to the relevant instructions in the APP user manual.
errno_t set_compliant_speed_limit(double vel, double angularVel);
Get torque reference center
Get torque reference center.
- Parameter description
- refPoint 0 represents the end flange center (or sensor center), 1 represents the center of the currently active tool coordinate system.
errno_t get_torque_ref_point(int *refPoint);
Set torque reference center
Set the torque reference center.
- Parameter description
- refPoint 0 represents the end flange center (or sensor center), 1 represents the center of the currently active tool coordinate system.
- For detailed meaning of this setting, please refer to the relevant instructions in the APP user manual.
errno_t set_torque_ref_point(int refPoint);
Set sensor sensitivity
Set the sensor sensitivity.
- Parameter description
- threshold is a 6-dimensional array, value range 0~1, the larger the value, the less sensitive the sensor, and the higher the threshold for responding to external interference.
errno_t set_end_sensor_sensitivity_threshold(FTxyz threshold);
Get sensor sensitivity
Get the sensor sensitivity.
- Parameter description
- threshold is a 6-dimensional array representing the percentage sensitivity set by the user.
- For detailed meaning of this setting, please refer to the relevant instructions in the APP user manual.
errno_t get_end_sensor_sensitivity_threshold(FTxyz *threshold);
- For detailed meaning of this setting, please refer to the relevant instructions in the APP user manual.
Code example:
int main()
{
std::cout << "Hello World!";
JAKAZuRobot demo;
//Log in to the controller. Replace 192.168.2.194 with the IP of your controller, and replace password with the jaka_sdk password you set in the app
demo.login_in("192.168.2.194",1,"jaka_sdk","password");
std::cout << "power on: " << demo.power_on() << std::endl;
std::cout << "enable: " << demo.enable_robot() << std::endl;
std::cout << "enable tool drive: " << demo.enable_tool_drive(1) << std::endl;
//Set tool_drive_frame
FTFrameType tool_drive_frame;
demo.set_tool_drive_frame(FTFrameType::FTFrame_World);
demo.get_tool_drive_frame(&tool_drive_frame);
std::cout << tool_drive_frame << std::endl;
//Set torque_ref_point
CartesianTran ref_point,ret_point;
ref_point.x = 1;
ref_point.y = 2;
ref_point.z = 2;
demo.set_ft_sensor_ref_point(&ref_point); //Set to follow the TCP
std::this_thread::sleep_for(std::chrono::milliseconds(500));
ret = demo.get_ft_sensor_ref_point(&ret_point);
std::cout << ret_point.x << ", " << ret_point.y << ", " << ret_point.z << std::endl;
//compatible speed limit
double vel, angvel;
demo.set_compliant_speed_limit(500, 60);
demo.get_compliant_speed_limit(&vel, &angvel);
std::cout << vel << ", " << angvel << std::endl; //should be: 500, 60
//torque sensor sensitivity threshold
FTxyz ft;
ft.fx = 0.3;
ft.fy = 0.3;
ft.fz = 0.3;
ft.tx = 0.3;
ft.ty = 0.3;
ft.tz = 0.3;
demo.set_end_sensor_sensitivity_threshold(ft);
std::this_thread::sleep_for(std::chrono::milliseconds(500));
demo.get_end_sensor_sensitivity_threshold(&ft);
std::cout << ft.fx << ", " << ft.fy << ", " << ft.fz << ", " << ft.tx << ", " << ft.ty << ", " << ft.tz << ", " << std::endl; //should be: 0.3, 0.3, 0.3, 0.3, 0.3, 0.3
//lock all other directions, only allow the z direction
ToolDriveConfig toolDriveCfg{};
RobotToolDriveCtrl robToolCfg;
for (int i = 0; i < 6; i++)
{
toolDriveCfg.axis = i;
if(i == 2){
toolDriveCfg.opt = 1;
}
else{
toolDriveCfg.opt = 0;
}
toolDriveCfg.rigidity = 0.3;
toolDriveCfg.rebound = 0;
demo.set_tool_drive_config(toolDriveCfg);
}
demo.get_tool_drive_config(&robToolCfg);
for (int i = 0; i < 6; i++)
{
std::cout << robToolCfg.config[i].axis << ", " << robToolCfg.config[i].opt << ", " << robToolCfg.config[i].rigidity << ", " << robToolCfg.config[i].rebound << std::endl;
}
//zero_end_sensor
std::cout << "zero: " << demo.zero_end_sensor() << std::endl;
//open tool drive
demo.enable_tool_drive(1);
int enable, state;
demo.get_tool_drive_state(&enable, &state);
std::this_thread::sleep_for(std::chrono::milliseconds(2000));
demo.enable_tool_drive(0);
//log out
demo.login_out();
std::cout << "end" << std::endl;
return 0;
}
Get basic sensor information
- Parameter description
- infos Pointer to
FTSensorBasicInfoStr, used to store the obtained data. - robot_id Target robot arm ID. If unspecified, the default value is 0.
- infos Pointer to
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_basic_info(FTSensorBasicInfoStr *infos, int robot_id = 0);
Get sensor soft limit rules
- Parameter description
- rules Pointer to
FTSensorSoftLimitRuleStr, used to store the obtained data. - robot_id The ID of the robot arm to be queried, default is 0.
- rules Pointer to
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_soft_limit_rules(FTSensorSoftLimitRuleStr *rules, int robot_id = 0);
Set sensor soft limit rules
- Parameter description
- rules Pointer to
FTSensorSoftLimitRuleStr, used to define the rules. - robot_id The ID of the robot arm, default is 0.
- rules Pointer to
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_sensor_soft_limit_rules(const FTSensorSoftLimitRuleStr *rules, int robot_id = 0);
Set sensor filter parameters
- Parameter description
- sensor_id The sensor to be set.
- filter: Pointer to filtering parameters.
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_sensor_filter(int sensor_id, const double *filter);
Get sensor filter parameters
- Parameter description
- sensor_id: Sensor ID.
- filter: Pointer to an array for storing parameters.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_filter(int sensor_id, double *filter);
Get sensor mode
- Parameter description
- sensor_id: Sensor ID to query.
- mode: Pointer to an integer for storing mode—1 means on, 0 means off.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_mode(int sensor_id, int *mode);
To zero the sensor.
- Parameter description
- sensor_id: Sensor ID to be zeroed.
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_sensor_zero(int sensor_id);
Set sensor threshold
- Parameter description
- sensor_id: Target sensor ID.
- threshold
: Pointerto an FTSensorThresholdStr structure containing the threshold value.
- Return value ERR_SUCC for success, others for failure
errno_t set_contact_force_threshold(int sensor_id, const FTSensorThresholdStr *threshold);
Get sensor threshold
- Parameter description
- sensor_id: Target sensor ID.
- threshold: Pointer to
FTSensorThresholdStrfor storing the threshold value.
- Return value ERR_SUCC for success, others for failure
errno_t get_contact_force_threshold(int sensor_id, FTSensorThresholdStr *threshold);
Set sensor reference point
- Parameter description
- ref_point: Pointer to
CartesianTrancontaining x, y,[ z offsets in meters]. - robot_id: robot arm ID, default value is 0.
- ref_point: Pointer to
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_sensor_ref_point(const CartesianTran *ref_point, int robot_id = 0);
Get sensor reference point
- Parameter description
- ref_point: Pointer to CartesianTran for receiving[ x, y,] z offsets in meters.
- robot_id: robot arm ID, default value is 0.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_ref_point(CartesianTran *ref_point, int robot_id = 0);
Get sensor data
- Parameter description
- sensor_id: Sensor ID.
- type: Data type to retrieve:
- 1 means execution torque (compatible interface),
- 2 means raw data,
- 3 means actual data with gravity and offset removed.
- data: Pointer to FTSensorDataStr, used to receive the result.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_data(int sensor_id, int type, FTSensorDataStr *data);
Get sensor load
- Parameter description
- sensor_id: Sensor ID.
- payload: Pointer to
PayLoad structure, used to store the result.
- Return value ERR_SUCC for success, others for failure
errno_t get_ft_sensor_payload(int sensor_id, PayLoad * payload);
Set sensor load
- Parameter description
- sensor_id: Sensor ID.
- payload_id: Payload configuration ID to be assigned.
- Return value ERR_SUCC for success, others for failure
errno_t set_ft_sensor_payload(int sensor_id, int payload_id);
Get ID of the sensor currently connected to the robot arm
- Parameter description
- sensor_ids:
Pointer to FTLinkedSensorIDStr, used to receive the result. - robot_id: robot arm ID, default value is 0.
- sensor_ids:
- Return value ERR_SUCC for success, others for failure
errno_t get_linked_ft_sensor_id(FTLinkedSensorIDStr *sensor_ids, int robot_id = 0);
Add sensor
- Parameter description
- config: Pointer to
FTSensorConfigStrcontaining sensor configuration information. - robot_id: robot arm ID, default value is 0.
- config: Pointer to
- Return value ERR_SUCC for success, others for failure
errno_t add_ft_sensor(const FTSensorConfigStr *config, int robot_id = 0);
Delete sensor
- Parameter description
- sensor_id: The sensor ID to be deleted.
- robot_id: robot arm ID, default value is 0.
- Return value ERR_SUCC for success, others for failure
errno_t remove_ft_sensor(int sensor_id, int robot_id = 0);
Set speed limit in force control mode
- Parameter description
- limit:
Pointer to VelocityLimit structure, used to specify linear and angular velocity limits. - robot_id: robot arm ID, default value is 0.
- limit:
- Return value ERR_SUCC for success, others for failure
errno_t set_force_ctrl_vel_limit(const VelocityLimit *limit, int robot_id = 0);
Get speed limit in force control mode
- Parameter description
- limit: Pointer to
VelocityLimit, used to receive velocity limit parameters. - robot_id: robot arm ID, default value is 0.
- limit: Pointer to
- Return value ERR_SUCC for success, others for failure
errno_t get_force_ctrl_vel_limit(VelocityLimit *limit, int robot_id = 0);
Set approach speed limit
Approaching speed limit refers to: Setting the speed limit for the movement of the robot arm’s end before it contacts an object and generates force after constant force compliance control is enabled.
- Parameter description
- limit:
Pointer to VelocityLimit structure, used to specify velocity limit parameters. - robot_id: robot arm ID, default value is 0.
- limit:
- Return value ERR_SUCC for success, others for failure
errno_t set_approaching_vel_limit(const VelocityLimit *limit, int robot_id = 0);
Get approach speed limit
- Parameter description
- limit: Pointer to VelocityLimit structure, used to receive velocity limit parameters.
- robot_id: robot arm ID, default value is 0.
- Return value ERR_SUCC for success, others for failure
errno_t get_approaching_vel_limit(VelocityLimit *limit, int robot_id = 0);
Set constant-force compliance control mode parameters
- Parameter description
- axis: 0, x-axis; 1, y-axis; 2, z-axis; 3, rx; 4, ry; 5, rz.
- opt: 0 off, 1 on.
- ftUser: Damping, affects the stiffness that the robot arm's end exhibits toward the external environment. The larger this parameter, the greater the stiffness displayed at the end of the robot arm. Units are ×8 N·s/m (for x/y/z), ×16 Nm·s/(π·rad) (for rx/ry/rz)
- ftReboundFK: Rebound, represents the elastic coefficient between the robot arm's compliant control and the commanded trajectory (or initial position), with units of N/mm (for x/y/z) and Nm/rad (for rx/ry/rz).
- ftConstant: represents target force, units N (for x/y/z), Nm (for rx/ry/rz).
- For understanding the above parameters, please further refer to the relevant descriptions in the 172APP Programming Instruction Help section of the 172APP User Manual.
- Return value ERR_SUCC for success, others for failure
errno_t set_cst_force_ctrl_config(const AdmitCtrlType *config, int robot_id = 0);
Get constant-force compliance control mode parameters
- Parameter description
- config:
Pointer to AdmitCtrlType, used to receive compliance control configuration. - robot_id: robot arm ID, default value is 0.
- config:
- Return value ERR_SUCC for success, others for failure
errno_t get_cst_force_ctrl_config(AdmitCtrlType *config, int robot_id = 0);
Set constant-force compliance control tolerance
- Parameter description
- tol:
Pointerto the FTxyz structure, used to specify the tolerance value. - robot_id: robot arm ID, default value is 0.
- tol:
- Return value ERR_SUCC for success, others for failure
errno_t set_cst_force_ctrl_tol(const FTxyz *tol, int robot_id = 0);
Get constant-force compliance control tolerance
- Parameter description
- tol: Pointer to the FTxyz structure, used to receive the tolerance value.
- robot_id: robot arm ID, default value is 0.
- Return value ERR_SUCC for success, others for failure
errno_t get_cst_force_ctrl_tol(FTxyz *tol, int robot_id = 0);
FTP Service
Initialize FTP client
Initialize the FTP client, establish connection with the control cabinet, and export program, track
- Return value ERR_SUCC for success, others for failure
errno_t init_ftp_client();
FTP Upload
Upload the specified type and name of file from local to the controller
- Parameter description
- remote: Absolute path of the file name inside the controller; if it is a folder, it must end with "/"
- local: Absolute path of the local file name; if it is a folder, it must end with "/"
- opt: 1 single file, 2 folder
- Return value ERR_SUCC for success, others for failure
- @note Windows C++/ Windows C#: input parameter encoding is GBK; Linux is UTF-8
errno_t upload_file(char *local, char *remote, int opt);
FTP Download
Download the specified type and name of file from the controller to local
- Parameter description
- remote: Absolute path of the file name inside the controller; if it is a folder, it must end with "/"
- local: Absolute path of the local file name for download; if it is a folder, it must end with "/"
- opt: 1 single file, 2 folder
- Return value ERR_SUCC for success, others for failure
- Windows C++/ Windows C#: input parameter encoding is GBK; Linux is UTF-8
errno_t download_file(char *local, char *remote, int opt);
FTP Directory Query
Query FTP directory
- Parameter description
- remote: Original file name inside the controller; query track "/track/", query script program "/program/"
- opt: 0 file name and subdirectory name, 1 file name, 2 subdirectory name
- ret Returned query result
- Return value ERR_SUCC for success, others for failure
- Windows C++/ Windows C#: input parameter encoding is GBK; Linux is UTF-8
errno_t get_ftp_dir(const char *remotedir, int type, char *ret);
FTP delete
Delete files of the specified type and name from the controller
- Parameter description
- remote Internal file name of the controller
- opt: 1 single file, 2 folder
- Return value ERR_SUCC for success, others for failure
- Windows C++/ Windows C#: input parameter encoding is GBK; Linux is UTF-8
errno_t del_ftp_file(char *remote, int opt);
FTP rename
Rename files of the specified type and name in the controller
- Parameter description
- remote Original internal file name of the controller
- des Target name for renaming
- opt: 1 single file, 2 folder
- Return value ERR_SUCC for success, others for failure
- Windows C++/ Windows C#: input parameter encoding is GBK; Linux is UTF-8
errno_t rename_ftp_file(char *remote, char *des, int opt);
Close FTP client
Disconnect from the controller FTP connection
- Return value ERR_SUCC for success, others for failure
errno_t close_ftp_client();
Interface call return value list and troubleshooting
| Error codes | Description | Handling suggestions |
|---|---|---|
| 0 | success | null |
| 2 | interface error or controller not supported | Check the controller and SDK version information, upgrade or use another interface |
| -1 | invalid handler | Please check whether login is done before calling the interface |
| -2 | invalid parameter | Please check whether the parameters are correct |
| -3 | failed to connect | Please check the network connection status, or whether the robot IP is correct |
| -4 | inverse kinematics error | Inverse kinematics failed, please check the current coordinate system, or whether the reference joint angles are reasonable |
| -5 | emergency stop | Emergency stop state, status retained |
| -6 | not powered on | Not powered on |
| -7 | not enabled | Not enabled |
| -8 | not in servo mode | Not in servo mode. When executing servoJP, you must first enter servo mode. Please check whether the corresponding interface is called |
| -9 | must disable enable before powering off | Must disable enable before powering off |
| -10 | cannot operate, program is running | Cannot operate, a program is currently running. Please close the program first |
| -11 | cannot open file, or file does not exist | Cannot open file, or file does not exist |
| -12 | motion abnormal | Abnormal movement, possibly near a singularity point or exceeding robot movement limits |
| -14 | ftp error | ftp abnormal |
| -15 | socket msg or value oversize | Exceeding limit abnormal |
| -16 | kine_forward error | Forward kinematics failed |
| -17 | not support empty folder | Empty folders are not supported |
| -20 | protective stop | Safeguard (Protective) Stop |
| -21 | emergency stop | Emergency stop |
| -22 | on soft limit | In soft limit position, manual drag of the robot is not possible; use the teaching function in the APP to approach the soft limit |
| -30 | fail to encode cmd string | Command encoding failed, usually due to an error while parsing the message returned by the controller |
| -31 | fail to decode cmd string | Command decoding failed, usually due to an error while parsing the message returned by the controller |
| -32 | fail to uncompress port 10004 string | Failed to decompress data from port 10004, possibly due to network fluctuations or excessive data size |
| -40 | move linear error | Linear movement failed, please check if there are any singular regions in the path |
| -41 | move joint error | Joint movement failed, please check the set joint angles |
| -42 | move circular error | Arc motion failed, please check the set parameters |
| -50 | block_wait timeout | Blocking wait timeout |
| -51 | power on timeout | Power-on timeout |
| -52 | power off timeout | Power-off timeout |
| -53 | enable timeoff | Enable timeout |
| -54 | disable timeout | Disable timeout |
| -55 | set userframe timeout | Setting user coordinate system timeout |
| -56 | set tool timeout | Setting tool coordinate system timeout |
| -57 | edg init failed | EDG function initialization failed |
| -58 | edg is running, cannot use servo_j or servo_p | EDG function is running, cannot use servo_j or servo_p interface |
| -59 | Current EDG mode does not support using edg_servo_j or edg_servo_p. | EDG function is running, cannot use edg_servo_j or edg_servo_p interface |
| -60 | set io timeout | Setting IO timeout |
| -61 | operation timeout | Interface timeout |
| -62 | servo queue is full | Servo queue is full |
| -63 | servo is not running | Servo mode is not started |
| -9997 | not implement | Interface not implemented |
| -9998 | deprecated interface | Interface will be removed in the future (function still available) |
| -9999 | obsolete interface | Interface will be removed in the future (function unavailable) |
Issue feedback
If there are any inaccurate descriptions or mistakes in the document, we kindly ask readers for their understanding and corrections. If you find any problems or wish to provide suggestions while reading, you can send an email to support@jaka.com , and we will reply to you as soon as possible.
