Skip to content

Commit d226127

Browse files
committed
[Fix] rename parameter ik to motion_type and update docs
1 parent e38938f commit d226127

File tree

9 files changed

+145
-99
lines changed

9 files changed

+145
-99
lines changed

ReadMe.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -11,10 +11,10 @@
1111
- Protect the arm before unlocking the motor.
1212

1313
## Update Summary
14-
- > ### 1.11.4
14+
- > ### 1.11.5
1515
- Optimization pause time is too long (wait=true)
1616
- Add common motion api (Enabled after firmware version 1.11.100)
17-
- The Cartesian motion-related interface adds IK parameters to find an IK value for the given target position for joint planning (Enabled after firmware version 1.11.100)
17+
- The Cartesian motion-related interface adds the motion_type parameter to determine the planning method (Enabled after firmware version 1.11.100)
1818

1919
- > ### 1.11.0
2020
- Support transparent transmission (240/241)

demo/csharp_studio/xarm/xarm_wrapper.cc

+6-6
Original file line numberDiff line numberDiff line change
@@ -112,11 +112,11 @@ namespace XArmWrapper
112112
int __stdcall clean_error(void) {
113113
return arm->clean_error();
114114
}
115-
int __stdcall set_position(fp32 pose[6], fp32 radius, fp32 speed, fp32 acc, fp32 mvtime, bool wait, fp32 timeout, bool relative, unsigned char ik) {
116-
return arm->set_position(pose, radius, speed, acc, mvtime, wait, timeout, relative, ik);
115+
int __stdcall set_position(fp32 pose[6], fp32 radius, fp32 speed, fp32 acc, fp32 mvtime, bool wait, fp32 timeout, bool relative, unsigned char motion_type) {
116+
return arm->set_position(pose, radius, speed, acc, mvtime, wait, timeout, relative, motion_type);
117117
}
118-
int __stdcall set_tool_position(fp32 pose[6], fp32 speed, fp32 acc, fp32 mvtime, bool wait, fp32 timeout, fp32 radius, unsigned char ik) {
119-
return arm->set_tool_position(pose, speed, acc, mvtime, wait, timeout, radius, ik);
118+
int __stdcall set_tool_position(fp32 pose[6], fp32 speed, fp32 acc, fp32 mvtime, bool wait, fp32 timeout, fp32 radius, unsigned char motion_type) {
119+
return arm->set_tool_position(pose, speed, acc, mvtime, wait, timeout, radius, motion_type);
120120
}
121121
int __stdcall set_servo_angle(fp32 angles[7], fp32 speed, fp32 acc, fp32 mvtime, bool wait, fp32 timeout, fp32 radius, bool relative) {
122122
return arm->set_servo_angle(angles, speed, acc, mvtime, wait, timeout, radius, relative);
@@ -351,8 +351,8 @@ namespace XArmWrapper
351351
int __stdcall is_tcp_limit(fp32 pose[6], int *limit) {
352352
return arm->is_tcp_limit(pose, limit);
353353
}
354-
int __stdcall set_position_aa(fp32 pose[6], fp32 speed, fp32 acc, fp32 mvtime, bool is_tool_coord, bool relative, bool wait, fp32 timeout, fp32 radius, unsigned char ik) {
355-
return arm->set_position_aa(pose, speed, acc, mvtime, is_tool_coord, relative, wait, timeout, radius, ik);
354+
int __stdcall set_position_aa(fp32 pose[6], fp32 speed, fp32 acc, fp32 mvtime, bool is_tool_coord, bool relative, bool wait, fp32 timeout, fp32 radius, unsigned char motion_type) {
355+
return arm->set_position_aa(pose, speed, acc, mvtime, is_tool_coord, relative, wait, timeout, radius, motion_type);
356356
}
357357
int __stdcall set_servo_cartesian_aa(fp32 pose[6], fp32 speed, fp32 acc, bool is_tool_coord, bool relative) {
358358
return arm->set_servo_cartesian_aa(pose, speed, acc, is_tool_coord, relative);

demo/csharp_studio/xarm/xarm_wrapper.h

+3-3
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,8 @@ namespace XArmWrapper {
3838
extern "C" __declspec(dllexport) int __stdcall clean_warn(void);
3939
extern "C" __declspec(dllexport) int __stdcall clean_error(void);
4040

41-
extern "C" __declspec(dllexport) int __stdcall 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 ik = 0);
42-
extern "C" __declspec(dllexport) int __stdcall set_tool_position(fp32 pose[6], fp32 speed=0, fp32 acc=0, fp32 mvtime=0, bool wait=false, fp32 timeout=0, fp32 radius = -1, unsigned char ik = 0);
41+
extern "C" __declspec(dllexport) int __stdcall 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);
42+
extern "C" __declspec(dllexport) int __stdcall set_tool_position(fp32 pose[6], fp32 speed=0, fp32 acc=0, fp32 mvtime=0, bool wait=false, fp32 timeout=0, fp32 radius = -1, unsigned char motion_type = 0);
4343
extern "C" __declspec(dllexport) int __stdcall 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);
4444
extern "C" __declspec(dllexport) int __stdcall set_servo_angle_j(fp32 angles[7], fp32 speed=0, fp32 acc=0, fp32 mvtime=0);
4545
extern "C" __declspec(dllexport) int __stdcall set_servo_cartesian(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool is_tool_coord = false);
@@ -123,7 +123,7 @@ namespace XArmWrapper {
123123
extern "C" __declspec(dllexport) int __stdcall set_cgpio_digital_with_xyz(int ionum, int value, float xyz[3], float tol_r);
124124
extern "C" __declspec(dllexport) int __stdcall set_cgpio_analog_with_xyz(int ionum, float value, float xyz[3], float tol_r);
125125

126-
extern "C" __declspec(dllexport) int __stdcall set_position_aa(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool is_tool_coord = false, bool relative = false, bool wait = false, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, unsigned char ik = 0);
126+
extern "C" __declspec(dllexport) int __stdcall set_position_aa(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool is_tool_coord = false, bool relative = false, bool wait = false, fp32 timeout = NO_TIMEOUT, fp32 radius = -1, unsigned char motion_type = 0);
127127
extern "C" __declspec(dllexport) int __stdcall set_servo_cartesian_aa(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, bool is_tool_coord = false, bool relative = false);
128128

129129
extern "C" __declspec(dllexport) int __stdcall robotiq_reset(unsigned char ret_data[6] = NULL);

demo/csharp_studio/xarm_csharp_demo/XArmAPI.cs

+3-3
Original file line numberDiff line numberDiff line change
@@ -57,11 +57,11 @@ public static extern int create_instance(
5757
[DllImport("xarm.dll")]
5858
public static extern int set_position(float[] pose, float radius = -1,
5959
float speed = 0, float acc = 0, float mvtime = 0,
60-
bool wait = false, float timeout = NO_TIMEOUT, bool relative = false, byte ik = 0);
60+
bool wait = false, float timeout = NO_TIMEOUT, bool relative = false, byte motion_type = 0);
6161
[DllImport("xarm.dll")]
6262
public static extern int set_tool_position(float[] pose,
6363
float speed = 0, float acc = 0, float mvtime = 0,
64-
bool wait = false, float timeout = NO_TIMEOUT, float radius = -1, byte ik = 0);
64+
bool wait = false, float timeout = NO_TIMEOUT, float radius = -1, byte motion_type = 0);
6565
[DllImport("xarm.dll")]
6666
public static extern int set_servo_angle(float[] angles,
6767
float speed = 0, float acc = 0, float mvtime = 0,
@@ -224,7 +224,7 @@ public static extern int move_gohome(
224224
[DllImport("xarm.dll")]
225225
public static extern int is_tcp_limit(float[] pose, ref int limit);
226226
[DllImport("xarm.dll")]
227-
public static extern int set_position_aa(float[] pose, float speed = 0, float acc = 0, float mvtime = 0, bool is_tool_coord = false, bool relative = false, bool wait = false, float timeout = NO_TIMEOUT, float radius = -1, byte ik = 0);
227+
public static extern int set_position_aa(float[] pose, float speed = 0, float acc = 0, float mvtime = 0, bool is_tool_coord = false, bool relative = false, bool wait = false, float timeout = NO_TIMEOUT, float radius = -1, byte motion_type = 0);
228228
[DllImport("xarm.dll")]
229229
public static extern int set_servo_cartesian_aa(float[] pose, float speed = 0, float acc = 0, bool is_tool_coord = false, bool relative = false);
230230

doc/xarm_cplus_api.md

+40-19
Original file line numberDiff line numberDiff line change
@@ -514,9 +514,9 @@ __XArmAPI(const std::string &port="",
514514
> @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
515515
516516

517-
- __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 ik=0)__
518-
- __int set_position(fp32 pose[6], fp32 radius, bool wait, fp32 timeout=NO_TIMEOUT, bool relative=false, unsigned char ik=0)__
519-
- __int set_position(fp32 pose[6], bool wait, fp32 timeout=NO_TIMEOUT, bool relative=false, unsigned char ik=0)__
517+
- __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)__
518+
- __int set_position(fp32 pose[6], fp32 radius, bool wait, fp32 timeout=NO_TIMEOUT, bool relative=false, unsigned char motion_type=0)__
519+
- __int set_position(fp32 pose[6], bool wait, fp32 timeout=NO_TIMEOUT, bool relative=false, unsigned char motion_type=0)__
520520
> Set the position
521521
>     MoveLine: Linear motion
522522
>     MoveArcLine: Linear arc motion with interpolation
@@ -532,16 +532,23 @@ __XArmAPI(const std::string &port="",
532532
> @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
533533
> @param relative: relative move or not
534534
>     Note: only available if firmware_version >= 1.8.100
535-
> @param ik: whether to convert to joint planning through IK
536-
>     Note1: only available if firmware_version >= 1.11.100
537-
>     Note2: the specified radius is not supported, that is, the radius can only be -1
538-
>     Note3: if there is no suitable IK, a C40 error will be triggered
535+
> @param motion_type: motion planning type, default is 0
536+
>     motion_type == 0: default, linear planning
537+
>     motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
538+
>     motion_type == 2: direct transfer to IK using joint planning
539+
>     Note:
540+
>       1. only available if firmware_version >= 1.11.100
541+
>       2. when motion_type is 1 or 2, linear motion cannot be guaranteed
542+
>       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
543+
>         `speed = speed / max_tcp_speed * max_joint_speed`
544+
>         `acc = acc / max_tcp_acc * max_joint_acc`
545+
>       4. if there is no suitable IK, a C40 error will be triggered
539546
>
540547
> @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
541548
542549

543-
- __int set_tool_position(fp32 pose[6], fp32 speed=0, fp32 acc=0, fp32 mvtime=0, bool wait=false, fp32 timeout=NO_TIMEOUT, unsigned char ik=0)__
544-
- __int set_tool_position(fp32 pose[6], bool wait, fp32 timeout=NO_TIMEOUT, unsigned char ik=0)__
550+
- __int set_tool_position(fp32 pose[6], fp32 speed=0, fp32 acc=0, fp32 mvtime=0, bool wait=false, fp32 timeout=NO_TIMEOUT, unsigned char motion_type=0)__
551+
- __int set_tool_position(fp32 pose[6], bool wait, fp32 timeout=NO_TIMEOUT, unsigned char motion_type=0)__
545552
> Movement relative to the tool coordinate system
546553
>     MoveToolLine: Linear motion
547554
>     MoveToolArcLine: Linear arc motion with interpolation
@@ -556,10 +563,17 @@ __XArmAPI(const std::string &port="",
556563
> @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
557564
> @param radius: move radius, if radius less than 0, will MoveToolLine, else MoveToolArcLine
558565
>     Note: only available if firmware_version >= 1.11.100
559-
> @param ik: whether to convert to joint planning through IK
560-
>     Note1: only available if firmware_version >= 1.11.100
561-
>     Note2: the specified radius is not supported, that is, the radius can only be -1
562-
>     Note3: if there is no suitable IK, a C40 error will be triggered
566+
> @param motion_type: motion planning type, default is 0
567+
>     motion_type == 0: default, linear planning
568+
>     motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
569+
>     motion_type == 2: direct transfer to IK using joint planning
570+
>     Note:
571+
>       1. only available if firmware_version >= 1.11.100
572+
>       2. when motion_type is 1 or 2, linear motion cannot be guaranteed
573+
>       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
574+
>         `speed = speed / max_tcp_speed * max_joint_speed`
575+
>         `acc = acc / max_tcp_acc * max_joint_acc`
576+
>       4. if there is no suitable IK, a C40 error will be triggered
563577
>
564578
> @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
565579
@@ -1313,8 +1327,8 @@ __int move_gohome(bool wait=false, fp32 timeout=NO_TIMEOUT)__
13131327
> @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
13141328
13151329

1316-
- __int set_position_aa(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool is_tool_coord = false, bool relative = false, bool wait = false, fp32 timeout = NO_TIMEOUT, unsigned char ik = 0)__
1317-
- __int set_position_aa(fp32 pose[6], bool is_tool_coord, bool relative = false, bool wait = false, fp32 timeout = NO_TIMEOUT, unsigned char ik = 0)__
1330+
- __int set_position_aa(fp32 pose[6], fp32 speed = 0, fp32 acc = 0, fp32 mvtime = 0, bool is_tool_coord = false, bool relative = false, bool wait = false, fp32 timeout = NO_TIMEOUT, unsigned char motion_type = 0)__
1331+
- __int set_position_aa(fp32 pose[6], bool is_tool_coord, bool relative = false, bool wait = false, fp32 timeout = NO_TIMEOUT, unsigned char motion_type = 0)__
13181332
> Set the pose represented by the axis angle pose
13191333
>     MoveLineAA: Linear motion
13201334
>     MoveArcLineAA: Linear arc motion with interpolation
@@ -1331,10 +1345,17 @@ __int move_gohome(bool wait=false, fp32 timeout=NO_TIMEOUT)__
13311345
> @param timeout: maximum waiting time(unit: second), default is no timeout, only valid if wait is true
13321346
> @param radius: move radius, if radius less than 0, will MoveLineAA, else MoveArcLineAA
13331347
>     Note: only available if firmware_version >= 1.11.100
1334-
> @param ik: whether to convert to joint planning through IK
1335-
>     Note1: only available if firmware_version >= 1.11.100
1336-
>     Note2: the specified radius is not supported, that is, the radius can only be -1
1337-
>     Note3: if there is no suitable IK, a C40 error will be triggered
1348+
> @param motion_type: motion planning type, default is 0
1349+
>     motion_type == 0: default, linear planning
1350+
>     motion_type == 1: prioritize linear planning, and turn to IK for joint planning when linear planning is not possible
1351+
>     motion_type == 2: direct transfer to IK using joint planning
1352+
>     Note:
1353+
>       1. only available if firmware_version >= 1.11.100
1354+
>       2. when motion_type is 1 or 2, linear motion cannot be guaranteed
1355+
>       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
1356+
>         `speed = speed / max_tcp_speed * max_joint_speed`
1357+
>         `acc = acc / max_tcp_acc * max_joint_acc`
1358+
>       4. if there is no suitable IK, a C40 error will be triggered
13381359
>
13391360
> @return: see the [API Code Documentation](./xarm_api_code.md#api-code) for details.
13401361

include/xarm/core/instruction/uxbus_cmd.h

+6-6
Original file line numberDiff line numberDiff line change
@@ -121,12 +121,12 @@ class UxbusCmd {
121121
int clean_war(void);
122122
int set_brake(int axis, int en);
123123
int set_mode(int value, int detection_param = -1);
124-
int move_line(float mvpose[6], float mvvelo, float mvacc, float mvtime, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char ik = 0);
124+
int move_line(float mvpose[6], float mvvelo, float mvacc, float mvtime, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char motion_type = 0);
125125
int move_lineb(float mvpose[6], float mvvelo, float mvacc, float mvtime,
126-
float mvradii, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL);
126+
float mvradii, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char motion_type = 0);
127127
int move_joint(float mvjoint[7], float mvvelo, float mvacc, float mvtime, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL);
128128
int move_jointb(float mvjoint[7], float mvvelo, float mvacc, float mvradii, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL);
129-
int move_line_tool(float mvpose[6], float mvvelo, float mvacc, float mvtime, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char ik = 0);
129+
int move_line_tool(float mvpose[6], float mvvelo, float mvacc, float mvtime, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char motion_type = 0);
130130
int move_gohome(float mvvelo, float mvacc, float mvtime, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL);
131131
int move_servoj(float mvjoint[7], float mvvelo, float mvacc, float mvtime);
132132
int move_servo_cartesian(float mvpose[6], float mvvelo, float mvacc, float mvtime);
@@ -211,9 +211,9 @@ class UxbusCmd {
211211

212212
int get_pose_offset(float pose1[6], float pose2[6], float offset[6], int orient_type_in=0, int orient_type_out=0);
213213
int get_position_aa(float pose[6]);
214-
int move_line_aa(float mvpose[6], float mvvelo, float mvacc, float mvtime, int mvcoord=0, int relative=0, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char ik = 0);
214+
int move_line_aa(float mvpose[6], float mvvelo, float mvacc, float mvtime, int mvcoord=0, int relative=0, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char motion_type = 0);
215215
int move_servo_cart_aa(float mvpose[6], float mvvelo, float mvacc, int tool_coord=0, int relative=0);
216-
int move_relative(float mvpose[7], float mvvelo, float mvacc, float mvtime, float radius, int is_joint_motion = false, bool is_axis_angle = false, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char ik = 0);
216+
int move_relative(float mvpose[7], float mvvelo, float mvacc, float mvtime, float radius, int is_joint_motion = false, bool is_axis_angle = false, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char motion_type = 0);
217217

218218
int tgpio_delay_set_digital(int ionum, int value, float delay_sec);
219219
int cgpio_delay_set_digital(int ionum, int value, float delay_sec);
@@ -264,7 +264,7 @@ class UxbusCmd {
264264

265265
int iden_joint_friction(unsigned char sn[14], float *result);
266266

267-
int move_line_common(float mvpose[6], float mvvelo, float mvacc, float mvtime, float radius = -1.0, int coord = 0, bool is_axis_angle = false, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char ik = 0);
267+
int move_line_common(float mvpose[6], float mvvelo, float mvacc, float mvtime, float radius = -1.0, int coord = 0, bool is_axis_angle = false, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL, unsigned char motion_type = 0);
268268
int move_circle_common(float pose1[6], float pose2[6], float mvvelo, float mvacc, float mvtime, float percent, int coord = 0, bool is_axis_angle = false, unsigned char only_check_type = 0, unsigned char *only_check_result = NULL);
269269

270270
virtual void close(void);

0 commit comments

Comments
 (0)