-
Notifications
You must be signed in to change notification settings - Fork 29
/
xarm_api.h
2852 lines (2588 loc) · 120 KB
/
xarm_api.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/**
* Software License Agreement (MIT License)
*
* Copyright (c) 2022, UFACTORY, Inc.
*
* All rights reserved.
*
* @author Vinman <vinman.wen@ufactory.cc> <vinman.cub@gmail.com>
*/
#ifndef WRAPPER_XARM_API_H_
#define WRAPPER_XARM_API_H_
#include <iostream>
#include <functional>
#include <algorithm>
#include <thread>
#include <vector>
#include <assert.h>
#include <cmath>
#include <regex>
#include <map>
#include <string>
#include <stdarg.h>
#include <string.h>
#include "xarm/core/common/data_type.h"
#include "xarm/core/xarm_config.h"
#include "xarm/core/report_data.h"
#include "xarm/core/connect.h"
#include "xarm/core/instruction/uxbus_cmd.h"
#include "xarm/core/instruction/uxbus_cmd_ser.h"
#include "xarm/core/instruction/uxbus_cmd_tcp.h"
#include "xarm/core/instruction/uxbus_cmd_config.h"
#include "xarm/core/instruction/servo3_config.h"
#include "xarm/core/debug/debug_print.h"
#include "xarm/wrapper/common/utils.h"
#include "xarm/wrapper/common/timer.h"
#define REPORT_BUF_SIZE 1024
#define DEFAULT_IS_RADIAN false
#define RAD_DEGREE 57.295779513082320876798154814105
#define TIMEOUT_10 10
#define NO_TIMEOUT -1
#define SDK_VERSION "1.14.2"
typedef unsigned int u32;
typedef float fp32;
struct RobotIqStatus {
unsigned char gOBJ = 0;
unsigned char gSTA = 0;
unsigned char gGTO = 0;
unsigned char gACT = 0;
unsigned char kFLT = 0;
unsigned char gFLT = 0;
unsigned char gPR = 0;
unsigned char gPO = 0;
unsigned char gCU = 0;
};
struct LinearTrackStatus {
int pos;
int status;
int error;
unsigned char is_enabled;
unsigned char on_zero;
unsigned char sci;
unsigned char sco[2];
};
fp32 to_radian(fp32 val);
fp32 to_degree(fp32 val);
class XArmAPI {
public:
/**
* @param port: ip-address(such as "192.168.1.185")
* Note: this parameter is required if parameter do_not_open is false
* @param is_radian: set the default unit is radians or not, default is false
* @param do_not_open: do not open, default is false, if true, you need to manually call the connect interface.
* @param check_tcp_limit: reversed, whether checking tcp limit, default is true
* @param check_joint_limit: reversed, whether checking joint limit, default is true
* @param check_cmdnum_limit: whether checking command num limit, default is true
* @param check_robot_sn: whether checking robot sn, default is false
* @param check_is_ready: check robot is ready to move or not, default is true
* Note: only available if firmware_version < 1.5.20
* @param check_is_pause: check robot is pause or not, default is true
* @param max_callback_thread_count: max callback thread count, default is -1
* Note: greater than 0 means the maximum number of threads that can be used to process callbacks
* Note: equal to 0 means no thread is used to process the callback
* Note: less than 0 means no limit on the number of threads used for callback
* @param max_cmdnum: max cmdnum, default is 512
* Note: only available in the param `check_cmdnum_limit` is true
*/
XArmAPI(const std::string &port = "",
bool is_radian = DEFAULT_IS_RADIAN,
bool do_not_open = false,
bool check_tcp_limit = true,
bool check_joint_limit = true,
bool check_cmdnum_limit = true,
bool check_robot_sn = false,
bool check_is_ready = true,
bool check_is_pause = true,
int max_callback_thread_count = -1,
int max_cmdnum = 512,
int init_axis = 7,
bool debug = false,
std::string report_type = "rich",
bool baud_checkset = true);
~XArmAPI(void);
public:
int state; // state
int mode; // mode
int cmd_num; // cmd cache count
fp32 *joints_torque; // joints torque, fp32[7]{servo-1, ..., servo-7}
bool *motor_brake_states; // motor brake states, bool[8]{servo-1, ..., servo-7, reversed}
bool *motor_enable_states; // motor enable states, bool[8]{servo-1, ..., servo-7, reversed}
int error_code; // error code
int warn_code; // warn code
fp32 *tcp_load; // tcp load, fp32[4]{weight, x, y, z}
int collision_sensitivity; // collision sensitivity
int teach_sensitivity; // teach sensitivity
int device_type; // device type
int axis; // robot axis
int master_id;
int slave_id;
int motor_tid;
int motor_fid;
unsigned char version[30]; // version
unsigned char sn[40]; // sn
int *version_number; // version numbre
fp32 tcp_jerk; // tcp jerk
fp32 joint_jerk; // joint jerk
fp32 rot_jerk; // rot jerk
fp32 max_rot_acc; // max rot acc
fp32 *tcp_speed_limit; // fp32[2]{min, max}
fp32 *tcp_acc_limit; // fp32[2]{min, max}
fp32 last_used_tcp_speed;
fp32 last_used_tcp_acc;
fp32 *angles; // fp32[7]{servo-1, ..., servo-7}
fp32 *last_used_angles; // fp32[7]{servo-1, ..., servo-7}
fp32 *joint_speed_limit; // fp32[2]{min, max}
fp32 *joint_acc_limit; // fp32[2]{min, max}
fp32 last_used_joint_speed;
fp32 last_used_joint_acc;
fp32 *position; // fp32[6]{x, y, z, roll, pitch, yaw}
fp32 *position_aa; // fp32[6]{x, y, z, rx, ry, rz}
fp32 *last_used_position; // fp32[6]{x, y, z, roll, pitch, yaw}
fp32 *tcp_offset; // fp32[6]{x, y, z, roll, pitch, yaw}
fp32 *gravity_direction; // fp32[3]{x_direction, y_direction, z_direction}
fp32 realtime_tcp_speed;
fp32 *realtime_joint_speeds;
bool is_reduced_mode;
bool is_fence_mode;
bool is_report_current;
bool is_approx_motion;
bool is_cart_continuous;
fp32 *world_offset; // fp32[6]{x, y, z, roll, pitch, yaw}
fp32 *temperatures;
int count;
int iden_progress;
unsigned char *gpio_reset_config; // unsigned char[2]{cgpio_reset_enable, tgpio_reset_enable}
fp32 *ft_ext_force;
fp32 *ft_raw_force;
bool default_is_radian;
UxbusCmd *core;
struct RobotIqStatus robotiq_status;
struct LinearTrackStatus linear_track_status;
fp32 *voltages; // fp32[7]{servo-1, ..., servo-7}
fp32 *currents; // fp32[7]{servo-1, ..., servo-7}
int is_simulation_robot; // 0: off, 1: on
int is_collision_detection; // 0: off, 1: on
int collision_tool_type;
fp32 *collision_model_params; // fp32[6]{...}
int cgpio_state;
int cgpio_code;
int *cgpio_input_digitals; // int[2]{ digital-input-functional-gpio-state, digital-input-configuring-gpio-state }
int *cgpio_output_digitals; // int[2]{ digital-output-functional-gpio-state, digital-output-configuring-gpio-state }
fp32 *cgpio_intput_anglogs; // fp32[2] {analog-1-input-value, analog-2-input-value}
fp32 *cgpio_output_anglogs; // fp32[2] {analog-1-output-value, analog-2-output-value}
int *cgpio_input_conf; // fp32[8]{ CI0-conf, ... CI7-conf }
int *cgpio_output_conf; // fp32[8]{ CO0-conf, ... CO7-conf }
unsigned char only_check_result;
public:
/**
* @brief xArm has error/warn or not, only available in socket way
*/
bool has_err_warn(void);
/**
* @brief xArm has error or not, only available in socket way
*/
bool has_error(void);
/**
* @brief xArm has warn or not, only available in socket way
*/
bool has_warn(void);
/**
* @brief xArm is connected or not
*/
bool is_connected(void);
/**
* @brief Robot is lite6 or not
*/
bool is_lite6(void);
/**
* @brief Robot is UF850 or not
*/
bool is_850(void);
/**
* @brief xArm is reported or not, only available in socket way
*/
bool is_reported(void);
/**
* @brief Connect to xArm
*
* @param port: port name or the ip address
* @return:
* 0: success
* -1: port is empty
* -2: tcp control connect failed
* -3: tcp report connect failed
*/
int connect(const std::string &port = "");
/**
* @brief Disconnect
*/
void disconnect(void);
/* no use please */
void _handle_report_rich_data(void);
/* no use please */
void _handle_report_data(void);
void _handle_feedback_data(void);
/**
* @brief Get the xArm version
*
* @param version:
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_version(unsigned char version[40]);
/**
* @brief Get the xArm sn
*
* @param robot_sn:
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_robot_sn(unsigned char robot_sn[40]);
/**
* @brief Get the xArm state
*
* @param state: the state of xArm
* 1: in motion
* 2: sleeping
* 3: suspended
* 4: stopping
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_state(int *state);
/**
* @brief Control the xArm controller system
*
* @param value:
* 1: shutdown
* 2: reboot
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int system_control(int value = 1);
int shutdown_system(int value = 1);
/**
* @brief Get the cmd count in cache
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_cmdnum(int *cmdnum);
/**
* @brief Get the controller error and warn code
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_err_warn_code(int err_warn[2]);
/**
* @brief Get the cartesian position
*
* @param pose: the position of xArm, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_position(fp32 pose[6]);
/**
* @brief Get the servo angle
*
* @param angles: the angles of the servos, like [servo-1, ..., servo-7]
* if default_is_radian is true, the value of servo-1/.../servo-7 should be in radians
* if default_is_radian is false, The value of servo-1/.../servo-7 should be in degrees
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_servo_angle(fp32 angles[7], bool is_real = false);
/**
* @brief Get the joint states
* Note: only available if firmware_version >= 1.9.0
*
* @param position: the angles of the joints, like [angle-1, ..., angle-7]
* if default_is_radian is true, the value of angle-1/.../angle-7 should be in radians
* if default_is_radian is false, The value of angle-1/.../angle-7 should be in degrees
* @param velocity: the velocities of the joints, like [velo-1, ..., velo-7]
* if default_is_radian is true, the value of velo-1/.../velo-7 should be in radians
* if default_is_radian is false, The value of velo-1/.../velo-7 should be in degrees
* @param effort: the efforts of the joints, like [effort-1, ..., effort-7]
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_joint_states(fp32 jposition[7], fp32 velocity[7], fp32 effort[7], int num = 3);
/**
* @brief Motion enable
*
* @param enable: enable or not
* @param servo_id: servo id, 1-8, 8(enable/disable all servo)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int motion_enable(bool enable, int servo_id = 8);
/**
* @brief Set the xArm state
*
* @param state: state
* 0: sport state
* 3: pause state
* 4: stop state
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_state(int state);
/**
* @brief Set the xArm mode
*
* @param mode: mode
* 0: position control mode
* 1: servo motion mode
* 2: joint teaching mode
* 3: cartesian teaching mode (invalid)
* 4: joint velocity control mode
* 5: cartesian velocity control mode
* 6: joint online trajectory planning mode
* 7: cartesian online trajectory planning mode
* @param detection_param: teaching detection parameters, default is 0
* 0: turn on motion detection
* 1: trun off motion detection
* Note:
* 1. only available if firmware_version >= 1.10.1
* 2. only available if set_mode(2)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_mode(int mode, int detection_param = 0);
/**
* @brief Attach the servo
*
* @param servo_id: servo id, 1-8, 8(attach all servo)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_servo_attach(int servo_id);
/**
* @brief Detach the servo, be sure to do protective work before unlocking to avoid injury or damage.
*
* @param servo_id: servo id, 1-8, 8(detach all servo)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_servo_detach(int servo_id);
/**
* @brief Clean the controller error, need to be manually enabled motion and set state after clean error
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int clean_error(void);
/**
* @brief Clean the controller warn
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int clean_warn(void);
/**
* @brief Set the arm pause time, xArm will pause sltime second
*
* @param sltime: sleep second
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_pause_time(fp32 sltime);
/**
* @brief Set the sensitivity of collision
*
* @param sensitivity: sensitivity value, 0~5
* @param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_collision_sensitivity(int sensitivity, bool wait = true);
/**
* @brief Set the sensitivity of drag and teach
*
* @param sensitivity: sensitivity value, 1~5
* @param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_teach_sensitivity(int sensitivity, bool wait = true);
/**
* @brief Set the direction of gravity
*
* @param gravity_dir: direction of gravity, such as [x(mm), y(mm), z(mm)]
* @param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_gravity_direction(fp32 gravity_dir[3], bool wait = true);
/**
* @brief Clean current config and restore system default settings
* Note:
* 1. This interface will clear the current settings and restore to the original settings (system default settings)
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int clean_conf(void);
/**
* @brief Save config
* Note:
* 1. This interface can record the current settings and will not be lost after the restart.
* 2. The clean_conf interface can restore system default settings
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int save_conf(void);
/**
* @brief Set the position
* MoveLine: Linear motion
* MoveArcLine: Linear arc motion with interpolation
*
* @param pose: position, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param radius: move radius, if radius is None or radius less than 0, will MoveLine, else MoveArcLine
* @param speed: move speed (mm/s, rad/s), default is this.last_used_tcp_speed
* @param mvacc: move acceleration (mm/s^2, rad/s^2), default is this.last_used_tcp_acc
* @param mvtime: reserved, 0
* @param wait: whether to wait for the arm to complete, default is false
* @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
* @param relative: relative move or not
* Note: only available if firmware_version >= 1.8.100
* @param motion_type: motion planning type, default is 0
* motion_type == 0: default, linear planning
* motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
* motion_type == 2: direct transfer to IK using joint planning
* Note:
* 1. only available if firmware_version >= 1.11.100
* 2. when motion_type is 1 or 2, linear motion cannot be guaranteed
* 3. once IK is transferred to joint planning, the given Cartesian velocity and acceleration are converted into joint velocity and acceleration according to the percentage
* speed = speed / max_tcp_speed * max_joint_speed
* acc = acc / max_tcp_acc * max_joint_acc
* 4. if there is no suitable IK, a C40 error will be triggered
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_position(fp32 pose[6], fp32 radius = -1, fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool wait = false, fp32 timeout = NO_TIMEOUT, bool relative = false, unsigned char motion_type = 0);
int set_position(fp32 pose[6], fp32 radius, bool wait, fp32 timeout = NO_TIMEOUT, bool relative = false, unsigned char motion_type = 0);
int set_position(fp32 pose[6], bool wait, fp32 timeout = NO_TIMEOUT, bool relative = false, unsigned char motion_type = 0);
/**
* @brief Movement relative to the tool coordinate system
* MoveToolLine: Linear motion
* MoveToolArcLine: Linear arc motion with interpolation
*
* @param pose: the coordinate relative to the current tool coordinate systemion, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param speed: move speed (mm/s, rad/s), default is this.last_used_tcp_speed
* @param mvacc: move acceleration (mm/s^2, rad/s^2), default is this.last_used_tcp_acc
* @param mvtime: reserved, 0
* @param wait: whether to wait for the arm to complete, default is false
* @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
* @param radius: move radius, if radius less than 0, will MoveToolLine, else MoveToolArcLine
* Note: only available if firmware_version >= 1.11.100
* @param motion_type: motion planning type, default is 0
* motion_type == 0: default, linear planning
* motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
* motion_type == 2: direct transfer to IK using joint planning
* Note:
* 1. only available if firmware_version >= 1.11.100
* 2. when motion_type is 1 or 2, linear motion cannot be guaranteed
* 3. once IK is transferred to joint planning, the given Cartesian velocity and acceleration are converted into joint velocity and acceleration according to the percentage
* speed = speed / max_tcp_speed * max_joint_speed
* acc = acc / max_tcp_acc * max_joint_acc
* 4. if there is no suitable IK, a C40 error will be triggered
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_tool_position(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool wait = false, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, unsigned char motion_type = 0);
int set_tool_position(fp32 pose[6], bool wait, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, unsigned char motion_type = 0);
/**
* @brief Set the servo angle
*
* @param angles: angles, like [servo-1, ..., servo-7]
* if default_is_radian is true, the value of servo-1/.../servo-7 should be in radians
* if default_is_radian is false, The value of servo-1/.../servo-7 should be in degrees
* @param servo_id: servo id, 1~7, specify the joint ID to set
* @param angle: servo angle, use with servo_id parameters
* @param speed: move speed (rad/s or °/s), default is this.last_used_joint_speed
* if default_is_radian is true, the value of speed should be in radians
* if default_is_radian is false, The value of speed should be in degrees
* @param acc: move acceleration (rad/s^2 or °/s^2), default is this.last_used_joint_acc
* if default_is_radian is true, the value of acc should be in radians
* if default_is_radian is false, The value of acc should be in degrees
* @param mvtime: reserved, 0
* @param wait: whether to wait for the arm to complete, default is false
* @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
* @param radius: move radius, if radius less than 0, will MoveJoint, else MoveArcJoint
* Note: the blending radius cannot be greater than the track length.
* Note: only available if firmware_version >= 1.5.20
* @param relative: relative move or not
* Note: only available if firmware_version >= 1.8.100
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_servo_angle(fp32 angles[7], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool wait = false, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, bool relative = false);
int set_servo_angle(fp32 angles[7], bool wait, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, bool relative = false);
int set_servo_angle(int servo_id, fp32 angle, fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool wait = false, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, bool relative = false);
int set_servo_angle(int servo_id, fp32 angle, bool wait, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, bool relative = false);
/**
* @brief Servo_j motion, execute only the last instruction, need to be set to servo motion mode(this.set_mode(1))
*
* @param angles: angles, like [servo-1, ..., servo-7]
* if default_is_radian is true, the value of servo-1/.../servo-7 should be in radians
* if default_is_radian is false, The value of servo-1/.../servo-7 should be in degrees
* @param speed: reserved, move speed (rad/s or °/s)
* if default_is_radian is true, the value of speed should be in radians
* if default_is_radian is false, The value of speed should be in degrees
* @param acc: reserved, move acceleration (rad/s^2 or °/s^2)
* if default_is_radian is true, the value of acc should be in radians
* if default_is_radian is false, The value of acc should be in degrees
* @param mvtime: reserved, 0
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_servo_angle_j(fp32 angles[7], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0);
/**
* @brief Servo cartesian motion, execute only the last instruction, need to be set to servo motion mode(this.set_mode(1))
*
* @param pose: position, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param speed: reserved, move speed (mm/s)
* @param mvacc: reserved, move acceleration (mm/s^2)
* @param mvtime: reserved, 0
* @param is_tool_coord: is tool coordinate or not
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_servo_cartesian(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool is_tool_coord = false);
/**
* @brief The motion calculates the trajectory of the space circle according to the three-point coordinates.
* The three-point coordinates are (current starting point, pose1, pose2).
*
* @param pose1: cartesian position, [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param pose2: cartesian position, [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param percent: the percentage of arc length and circumference of the movement
* @param speed: move speed (mm/s, rad/s), default is this.last_used_tcp_speed
* @param mvacc: move acceleration (mm/s^2, rad/s^2), default is this.last_used_tcp_acc
* @param mvtime: 0, reserved
* @param wait: whether to wait for the arm to complete, default is false
* @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
* @param is_tool_coord: is tool coord or not, default is false, only available if firmware_version >= 1.11.100
* @param is_axis_angle: is axis angle or not, default is false, only available if firmware_version >= 1.11.100
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int move_circle(fp32 pose1[6], fp32 pose2[6], fp32 percent, fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool wait = false, fp32 timeout = NO_TIMEOUT, bool is_tool_coord = false, bool is_axis_angle = false);
/**
* @brief Move to go home (Back to zero)
*
* @param speed: move speed (rad/s or °/s), default is 50 °/s
* if default_is_radian is true, the value of speed should be in radians
* if default_is_radian is false, The value of speed should be in degrees
* @param acc: move acceleration (rad/s^2 or °/s^2), default is 1000 °/s^2
* if default_is_radian is true, the value of acc should be in radians
* if default_is_radian is false, The value of acc should be in degrees
* @param mvtime: reserved, 0
* @param wait: whether to wait for the arm to complete, default is false
* @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int move_gohome(fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool wait = false, fp32 timeout = NO_TIMEOUT);
int move_gohome(bool wait, fp32 timeout = NO_TIMEOUT);
/**
* @brief Reset
*
* @param wait: whether to wait for the arm to complete, default is false
* @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
void reset(bool wait = false, fp32 timeout = NO_TIMEOUT);
/**
* @brief Emergency stop
*/
void emergency_stop(void);
/**
* @brief Set the tool coordinate system offset at the end
*
* @param pose_offset: tcp offset, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param wait: whether to wait for the robotic arm to stop or all previous queue commands to be executed or cleared before setting
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_tcp_offset(fp32 pose_offset[6], bool wait = true);
/**
* @brief Set the load
*
* @param weight: load weight (unit: kg)
* @param center_of_gravity: tcp load center of gravity, like [x(mm), y(mm), z(mm)]
* @param wait: whether to wait for the command to be executed or the robotic arm to stop
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_tcp_load(fp32 weight, fp32 center_of_gravity[3], bool wait = false);
/**
* @brief Set the translational jerk of Cartesian space
*
* @param jerk: jerk (mm/s^3)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_tcp_jerk(fp32 jerk);
/**
* @brief Set the max translational acceleration of Cartesian space
*
* @param acc: max acceleration (mm/s^2)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_tcp_maxacc(fp32 acc);
/**
* @brief Set the jerk of Joint space
*
* @param jerk: jerk (°/s^3 or rad/s^3)
* if default_is_radian is true, the value of jerk should be in radians
* if default_is_radian is false, The value of jerk should be in degrees
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_joint_jerk(fp32 jerk);
/**
* @brief Set the max acceleration of Joint space
*
* @param acc: max acceleration (°/s^2 or rad/s^2)
* if default_is_radian is true, the value of jerk should be in radians
* if default_is_radian is false, The value of jerk should be in degrees
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_joint_maxacc(fp32 acc);
/**
* @brief Get inverse kinematics
*
* @param pose: source pose, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param angles: target angles, like [servo-1, ..., servo-7]
* if default_is_radian is true, the value of servo-1/.../servo-7 should be in radians
* if default_is_radian is false, The value of servo-1/.../servo-7 should be in degrees
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_inverse_kinematics(fp32 pose[6], fp32 angles[7]);
/**
* @brief Get forward kinematics
*
* @param angles: source angles, like [servo-1, ..., servo-7]
* if default_is_radian is true, the value of servo-1/.../servo-7 should be in radians
* if default_is_radian is false, The value of servo-1/.../servo-7 should be in degrees
* @param pose: target pose, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_forward_kinematics(fp32 angles[7], fp32 pose[6]);
/**
* @brief Check the tcp pose is in limit
*
* @param pose: pose, like [x(mm), y(mm), z(mm), roll(rad or °), pitch(rad or °), yaw(rad or °)]
* if default_is_radian is true, the value of roll/pitch/yaw should be in radians
* if default_is_radian is false, The value of roll/pitch/yaw should be in degrees
* @param limit: 1: limit, 0: no limit
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int is_tcp_limit(fp32 pose[6], int *limit);
/**
* @brief Check the joint is in limit
*
* @param angles: angles, like [servo-1, ..., servo-7]
* if default_is_radian is true, the value of servo-1/.../servo-7 should be in radians
* if default_is_radian is false, The value of servo-1/.../servo-7 should be in degrees
* @param limit: 1: limit, 0: no limit
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int is_joint_limit(fp32 angles[7], int *limit);
/**
* @brief Set the gripper enable
*
* @param enable: enable or not
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_gripper_enable(bool enable);
/**
* @brief Set the gripper mode
*
* @param mode: 1: location mode, 2: speed mode(no use), 3: torque mode(no use)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_gripper_mode(int mode);
/**
* @brief Get the gripper position
*
* @param pos: used to store the results obtained
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_gripper_position(fp32 *pos);
/**
* @brief Set the gripper position
*
* @param pos: gripper position
* @param wait: wait or not, default is false
* @param timeout: maximum waiting time(unit: second), default is 10s, only valid if wait is true
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_gripper_position(fp32 pos, bool wait = false, fp32 timeout = 10, bool wait_motion = true);
/**
* @brief Set the gripper speed
*
* @param speed:
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_gripper_speed(fp32 speed);
/**
* @brief Get the gripper error code
*
* @param err: used to store the results obtained
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_gripper_err_code(int *err);
/**
* @brief Clean the gripper error
*
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int clean_gripper_error(void);
/**
* @brief Get the digital value of the Tool GPIO
*
* @param io0_value: the digital value of Tool GPIO-0
* @param io1_value: the digital value of Tool GPIO-1
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_tgpio_digital(int *io0_value, int *io1_value);
/**
* @brief Set the digital value of the specified Tool GPIO
*
* @param ionum: ionum, 0 or 1
* @param value: the digital value of the specified io
* @param delay_sec: delay effective time from the current start, in seconds, default is 0(effective immediately)
* @param sync: whether to execute in the motion queue, set to false to execute immediately(default is true)
* 1. only available if firmware_version >= 2.4.101
* 2. only available if delay_sec <= 0
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_tgpio_digital(int ionum, int value, float delay_sec = 0, bool sync = true);
/**
* @brief Get the analog value of the specified Tool GPIO
*
* @param ionum: ionum, 0 or 1
* @param value: the analog value of the specified tool io
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_tgpio_analog(int ionum, float *value);
/**
* @brief Get the digital value of the specified Controller GPIO
*
* @param digitals: the values of the controller GPIO(0-7)
* @param digitals2: the values of the controller GPIO(8-15)
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_cgpio_digital(int *digitals, int *digitals2 = NULL);
/**
* @brief Get the analog value of the specified Controller GPIO
*
* @param ionum: ionum, 0 or 1
* @param value: the analog value of the specified controller io
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_cgpio_analog(int ionum, fp32 *value);
/**
* @brief Set the digital value of the specified Controller GPIO
*
* @param ionum: ionum, 0 ~ 15
* @param value: the digital value of the specified io
* @param delay_sec: delay effective time from the current start, in seconds, default is 0(effective immediately)
* @param sync: whether to execute in the motion queue, set to false to execute immediately(default is true)
* 1. only available if firmware_version >= 2.4.101
* 2. only available if delay_sec <= 0
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_cgpio_digital(int ionum, int value, float delay_sec = 0, bool sync = true);
/**
* @brief Set the analog value of the specified Controller GPIO
*
* @param ionum: ionum, 0 or 1
* @param value: the analog value of the specified io
* @param sync: whether to execute in the motion queue, set to false to execute immediately(default is true)
* 1. only available if firmware_version >= 2.4.101
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_cgpio_analog(int ionum, fp32 value, bool sync = true);
/**
* @brief Set the digital input functional mode of the Controller GPIO
*
* @param ionum: ionum, 0 ~ 15
* @param fun: functional mode
* 0: general input
* 1: external emergency stop
* 2: protection reset
* 11: offline task
* 12: teaching mode
* 13: reduced mode
* 14: enable arm
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_cgpio_digital_input_function(int ionum, int fun);
/**
* @brief Set the digital output functional mode of the specified Controller GPIO
*
* @param ionum: ionum, 0 ~ 15
* @param fun: functional mode
* 0: general output
* 1: emergency stop
* 2: in motion
* 11: has error
* 12: has warn
* 13: in collision
* 14: in teaching
* 15: in offline task
* 16: in reduced mode
* 17: is enabled
* 18: emergency stop is pressed
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int set_cgpio_digital_output_function(int ionum, int fun);
/**
* @brief Get the state of the Controller GPIO
*
* @param state: contorller gpio module state and controller gpio module error code
* state[0]: contorller gpio module state
* state[0] == 0: normal
* state[0] == 1:wrong
* state[0] == 6:communication failure
* state[1]: controller gpio module error code
* state[1] == 0: normal
* state[1] != 0:error code
* @param digit_io:
* digit_io[0]: digital input functional gpio state
* digit_io[1]: digital input configuring gpio state
* digit_io[2]: digital output functional gpio state
* digit_io[3]: digital output configuring gpio state
* @param analog:
* analog[0]: analog-0 input value
* analog[1]: analog-1 input value
* analog[2]: analog-0 output value
* analog[3]: analog-1 output value
* @param input_conf: digital(0-7) input functional info
* @param output_conf: digital(0-7) output functional info
* @param input_conf2: digital(8-15) input functional info
* @param output_conf2: digital(8-15) output functional info
* @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
*/
int get_cgpio_state(int *state, int *digit_io, fp32 *analog, int *input_conf, int *output_conf, int *input_conf2 = NULL, int *output_conf2 = NULL);
/**
* @brief Register the report data callback
*/
int register_report_data_callback(void(*callback)(XArmReportData *report_data_ptr));
int register_report_data_callback(std::function<void (XArmReportData *)> callback);
/**
* @brief Register the report location callback
*/
int register_report_location_callback(void(*callback)(const fp32 *pose, const fp32 *angles));
int register_report_location_callback(std::function<void (const fp32*, const fp32*)> callback);
/**
* @brief Register the connect status changed callback
*/
int register_connect_changed_callback(void(*callback)(bool connected, bool reported));
int register_connect_changed_callback(std::function<void (bool, bool)> callback);
/**
* @brief Register the state status changed callback
*/
int register_state_changed_callback(void(*callback)(int state));
int register_state_changed_callback(std::function<void (int)> callback);
/**
* @brief Register the mode changed callback
*/
int register_mode_changed_callback(void(*callback)(int mode));
int register_mode_changed_callback(std::function<void (int)> callback);
/**
* @brief Register the motor enable states or motor brake states changed callback
*/
int register_mtable_mtbrake_changed_callback(void(*callback)(int mtable, int mtbrake));
int register_mtable_mtbrake_changed_callback(std::function<void (int, int)> callback);
/**
* @brief Register the error code or warn code changed callback
*/
int register_error_warn_changed_callback(void(*callback)(int err_code, int warn_code));
int register_error_warn_changed_callback(std::function<void (int, int)> callback);
/**
* @brief Register the cmdnum changed callback
*/
int register_cmdnum_changed_callback(void(*callback)(int cmdnum));
int register_cmdnum_changed_callback(std::function<void (int)> callback);
/**
* @brief Register the temperature changed callback
*/
int register_temperature_changed_callback(void(*callback)(const fp32 *temps));
int register_temperature_changed_callback(std::function<void (const fp32*)> callback);