Skip to content

Commit 081e7c5

Browse files
authored
Merge pull request #90 from agilexrobotics/0_6_1_beta0
0.6.1
2 parents 8a46807 + 82ebe07 commit 081e7c5

File tree

15 files changed

+447
-18
lines changed

15 files changed

+447
-18
lines changed

CHANGELOG(ZH).MD

Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,33 @@
33
[Click to switch EN](CHANGELOG.MD)
44
=============
55

6+
Version 0.6.1
7+
=============
8+
9+
特性
10+
--------
11+
12+
- ✨ feat(can_encapsulation): 为`SendCanMessage`增加`dlc`以及`is_extended_id`参数
13+
- ✨ feat(interface,piper_msgs): 增加CPV模式选择以及注释说明
14+
- 可以通过`ModeCtrl(0x01, 0x05)`来切换到CPV模式
15+
16+
Bug修复
17+
---------
18+
19+
20+
其它
21+
---------
22+
23+
- 🧪 test(demo): 增加单独设定某个电机的关节限位的demo,`piper_set_motor_angle_limit.py`
24+
- 🧪 test(demo): 增加cpv模式下控制机械臂设置零点demo,`piper_set_joint_zero_cpv.py`
25+
- 📃 docs(interface): 修改CreateCanBus函数中bustype参数注释说明
26+
- 修改CreateCanBus函数中bustype有关的注释说明,说明预期参数为'socketcan'或'slcan'
27+
- 🧪 test(demo): 增加moveJ、moveL、moveP三个demo;同步demo中的README
28+
- 增加`piper_ctrl_moveJ.py`的demo,与`piper_ctrl_joint.py`内容相同;
29+
- 增加`piper_ctrl_moveL.py`的demo,效果为机械臂绘画正方形;
30+
- 增加`piper_ctrl_moveP.py`的demo,与`piper_ctrl_end_pose.py`内容相同;
31+
- 同步demo的README内容。
32+
633
Version 0.6.0
734
=============
835

CHANGELOG.MD

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,34 @@
33
[Click to switch ZH](CHANGELOG(ZH).MD)
44
=============
55

6+
Version 0.6.1
7+
=============
8+
9+
Features
10+
--------
11+
12+
- ✨ feat(can_encapsulation): Adds `dlc` and `is_extended_id` parameters to `SendCanMessage`
13+
- ✨ feat(interface,piper_msgs): Adds CPV mode selection and comments
14+
- CPV mode can be switched using `ModeCtrl(0x01, 0x05)`
15+
16+
Bug Fixes
17+
---------
18+
19+
None
20+
21+
Miscellaneous
22+
---------
23+
24+
- 🧪 test(demo): Added a demo for setting the joint limit of a single motor, `piper_set_motor_angle_limit.py`
25+
- 🧪 test(demo): Added a demo for setting the zero point of the robotic arm in CPV mode, `piper_set_joint_zero_cpv.py`
26+
- 📃 docs(interface): Modified the comment for the bustype parameter in the CreateCanBus function
27+
- Modified the comments related to bustype in the `CreateCanBus` function to specify that the expected parameter is `'socketcan'` or `'slcan'`.
28+
- 🧪 test(demo): Added three demos: moveJ, moveL, and moveP; synchronized the README in the demos.
29+
- Added a demo for `piper_ctrl_moveJ.py`, with the same content as `piper_ctrl_joint.py`;
30+
- Added a demo for `piper_ctrl_moveL.py`, which shows a robotic arm drawing a square;
31+
- Added a demo for `piper_ctrl_moveP.py`, with the same content as `piper_ctrl_end_pose.py`;
32+
- Synchronized the README content in the demos.
33+
634
Version 0.6.0
735
=============
836

asserts/V2/INTERFACE_V2.MD

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -130,7 +130,7 @@ The robot will immediately lose power and fall down, clearing all errors and int
130130

131131
```python
132132
def ModeCtrl(ctrl_mode: Literal[0x00, 0x01] = 0x01,
133-
move_mode: Literal[0x00, 0x01, 0x02, 0x03] = 0x01,
133+
move_mode: Literal[0x00, 0x01, 0x02, 0x03, 0x04, 0x05] = 0x01,
134134
move_spd_rate_ctrl: int = 50,
135135
is_mit_mode: Literal[0x00, 0xAD, 0xFF] = 0x00)
136136
```
@@ -147,6 +147,8 @@ Parameters:
147147
- 0x01: MOVE J (Joint)
148148
- 0x02: MOVE L (Linear)
149149
- 0x03: MOVE C (Circular)
150+
- 0x04: MOVE M (MIT) ---- Based on version V1.5-2 and later
151+
- 0x05: MOVE CPV ---- Based on version V1.8-1 and later
150152
- `move_spd_rate_ctrl`: Movement speed percentage (0-100)
151153
- `is_mit_mode`:
152154
- 0x00: Position-velocity mode

piper_sdk/demo/V2/README.MD

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,9 +33,14 @@ Instructions for activating the CAN module [can README](../../asserts/can_config
3333
|[`piper_ctrl_disable.py`](./piper_ctrl_disable.py)|Disable the robotic arm.|
3434
|[`piper_ctrl_enable.py`](./piper_ctrl_enable.py)|Enable the robotic arm.|
3535
|[`piper_ctrl_end_pose.py`](./piper_ctrl_end_pose.py)|Control the end-effector of the robotic arm.|
36+
|[`piper_ctrl_go_zero.py`](./piper_ctrl_go_zero.py)|Control the robotic arm to the zero position.|
3637
|[`piper_ctrl_gripper.py`](./piper_ctrl_gripper.py)|Control the robotic arm gripper.|
3738
|[`piper_ctrl_joint.py`](./piper_ctrl_joint.py)|Control the robotic arm joints.|
39+
|[`piper_ctrl_line.py`](./piper_ctrl_line.py)|Control the robotic arm in line motion mode.|
3840
|[`piper_ctrl_moveC.py`](./piper_ctrl_moveC.py)|Set the robotic arm to circular motion mode.|
41+
|[`piper_ctrl_moveJ.py`](./piper_ctrl_moveJ.py)|Control the joint movement of the robotic arm.|
42+
|[`piper_ctrl_moveL.py`](./piper_ctrl_moveL.py)|Control the robotic arm to draw a square on the XOY plane.|
43+
|[`piper_ctrl_moveP.py`](./piper_ctrl_moveP.py)|Control the movement of the robotic arm's end effector.|
3944
|[`piper_ctrl_reset.py`](./piper_ctrl_reset.py)|Reset the robotic arm. This must be executed once after setting it to teaching mode.|
4045
|[`piper_ctrl_stop.py`](./piper_ctrl_stop.py)|Stop the robotic arm and allow it to descend slowly. After use, reset and re-enable twice before resuming normal control.|
4146
|[`piper_read_all_fps.py`](./piper_read_all_fps.py)|Read the frequency of specified robotic arm data.|
@@ -50,13 +55,22 @@ Instructions for activating the CAN module [can README](../../asserts/can_config
5055
|[`piper_read_joint_ctrl.py`](./piper_read_joint_ctrl.py)|Read and print joint control messages.|
5156
|[`piper_read_joint_state.py`](./piper_read_joint_state.py)|Read and print joint state messages.|
5257
|[`piper_read_low_msg.py`](./piper_read_low_msg.py)|Read low-speed messages from the robotic arm.|
58+
|[`piper_read_mode_ctrl_canid_151.py`](./piper_read_mode_ctrl_canid_151.py)|Read the current mode control message from CAN ID 151.|
59+
|[`piper_read_mode_ctrl.py`](./piper_read_mode_ctrl.py)|Read the current mode control message from CAN ID 151.|
60+
|[`piper_read_resp_instruction.py`](./piper_read_resp_instruction.py)|Read the current instruction of the robotic arm.|
5361
|[`piper_read_status.py`](./piper_read_status.py)|Read the current status of the robotic arm.|
62+
|[`piper_read_tcp_pose.py`](./piper_read_tcp_pose.py)|Read the tool center point (TCP) pose.|
5463
|[`piper_read_version.py`](./piper_read_version.py)|Read the software version of each module in the robotic arm SDK.|
64+
|[`piper_set_can.py`](./piper_set_can.py)|Set the CAN bus parameters for the robotic arm.|
5565
|[`piper_set_gripper_zero.py`](./piper_set_gripper_zero.py)|Set the zero position of the robotic arm gripper.|
5666
|[`piper_set_init_default.py`](./piper_set_init_default.py)|Set all joint limits, maximum joint speeds, and joint accelerations to default values.|
67+
|[`piper_set_joint_zero_cpv.py`](./piper_set_joint_zero_cpv.py)|Set the joint motor zero-point position (including zero-point learning calibration in CPV mode).|
68+
|[`piper_set_joint_zero.py`](./piper_set_joint_zero.py)|Set the zero position of the robotic arm joints.|
5769
|[`piper_set_load.py`](./piper_set_load.py)|Set the end load parameters for the robotic arm.|
70+
|[`piper_set_log_level.py`](./piper_set_log_level.py)|Set the log level for the robotic arm SDK.|
5871
|[`piper_set_master.py`](./piper_set_master.py)|Set the robotic arm as the master arm.|
5972
|[`piper_set_mit.py`](./piper_set_mit.py)|Set the robotic arm to MIT mode, which provides the fastest response.|
73+
|[`piper_set_motor_angle_limit.py`](./piper_set_motor_angle_limit.py)|Set the angle limits for individual joint motors.|
6074
|[`piper_set_motor_max_acc_limit.py`](./piper_set_motor_max_acc_limit.py)|Set the maximum acceleration limit for individual joint motors.|
6175
|[`piper_set_sdk_param.py`](./piper_set_sdk_param.py)|Set SDK parameters for joint and gripper limits.|
6276
|[`piper_set_slave.py`](./piper_set_slave.py)|Set the robotic arm as the slave arm.|
Lines changed: 43 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,43 @@
1+
#!/usr/bin/env python3
2+
# -*-coding:utf8-*-
3+
# 注意demo无法直接运行,需要pip安装sdk后才能运行
4+
import time
5+
from piper_sdk import *
6+
7+
if __name__ == "__main__":
8+
piper = C_PiperInterface_V2("can0")
9+
piper.ConnectPort()
10+
while( not piper.EnablePiper()):
11+
time.sleep(0.01)
12+
piper.GripperCtrl(0,1000,0x01, 0)
13+
factor = 57295.7795 #1000*180/3.1415926
14+
position = [0,0,0,0,0,0,0]
15+
count = 0
16+
while True:
17+
count = count + 1
18+
# print(count)
19+
if(count == 0):
20+
print("1-----------")
21+
position = [0,0,0,0,0,0,0]
22+
elif(count == 300):
23+
print("2-----------")
24+
position = [0.2,0.2,-0.2,0.3,-0.2,0.5,0.08]
25+
elif(count == 600):
26+
print("1-----------")
27+
position = [0,0,0,0,0,0,0]
28+
count = 0
29+
30+
joint_0 = round(position[0]*factor)
31+
joint_1 = round(position[1]*factor)
32+
joint_2 = round(position[2]*factor)
33+
joint_3 = round(position[3]*factor)
34+
joint_4 = round(position[4]*factor)
35+
joint_5 = round(position[5]*factor)
36+
joint_6 = round(position[6]*1000*1000)
37+
piper.MotionCtrl_2(0x01, 0x01, 100, 0x00)
38+
piper.JointCtrl(joint_0, joint_1, joint_2, joint_3, joint_4, joint_5)
39+
piper.GripperCtrl(abs(joint_6), 1000, 0x01, 0)
40+
print(piper.GetArmStatus())
41+
print(position)
42+
time.sleep(0.005)
43+
Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,38 @@
1+
#!/usr/bin/env python3
2+
# -*-coding:utf8-*-
3+
# 注意demo无法直接运行,需要pip安装sdk后才能运行
4+
# piper机械臂直线模式demo
5+
# 注意机械臂工作空间内不要有障碍
6+
import time
7+
from piper_sdk import *
8+
9+
if __name__ == "__main__":
10+
piper = C_PiperInterface_V2("can0")
11+
piper.ConnectPort()
12+
while( not piper.EnablePiper()):
13+
time.sleep(0.01)
14+
15+
# 在XOY平面上画正方形
16+
# 切换至MOVEP模式,移动到初始位置
17+
piper.MotionCtrl_2(0x01, 0x00, 100, 0x00)
18+
piper.EndPoseCtrl(150000, -50000, 150000, -179900, 0, -179900)
19+
time.sleep(2)
20+
21+
# 切换至MOVEL模式
22+
piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
23+
piper.EndPoseCtrl(150000, 50000, 150000, -179900, 0, -179900)
24+
time.sleep(2)
25+
26+
piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
27+
piper.EndPoseCtrl(250000, 50000, 150000, -179900, 0, -179900)
28+
time.sleep(2)
29+
30+
piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
31+
piper.EndPoseCtrl(250000, -50000, 150000, -179900, 0, -179900)
32+
time.sleep(2)
33+
34+
piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
35+
piper.EndPoseCtrl(150000, -50000, 150000, -179900, 0, -179900)
36+
37+
38+
Lines changed: 71 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,71 @@
1+
#!/usr/bin/env python3
2+
# -*-coding:utf8-*-
3+
# 注意demo无法直接运行,需要pip安装sdk后才能运行
4+
import time
5+
from piper_sdk import *
6+
7+
if __name__ == "__main__":
8+
piper = C_PiperInterface_V2("can0")
9+
piper.ConnectPort()
10+
while( not piper.EnablePiper()):
11+
time.sleep(0.01)
12+
piper.GripperCtrl(0,1000,0x01, 0)
13+
factor = 1000
14+
position = [
15+
57.0, \
16+
0.0, \
17+
215.0, \
18+
0, \
19+
85.0, \
20+
0, \
21+
0]
22+
23+
count = 0
24+
while True:
25+
print(piper.GetArmEndPoseMsgs())
26+
count = count + 1
27+
if(count == 0):
28+
print("1-----------")
29+
position = [
30+
57.0, \
31+
0.0, \
32+
215.0, \
33+
0, \
34+
85.0, \
35+
0, \
36+
0]
37+
elif(count == 200):
38+
print("2-----------")
39+
position = [
40+
57.0, \
41+
0.0, \
42+
260.0, \
43+
0, \
44+
85.0, \
45+
0, \
46+
0]
47+
elif(count == 400):
48+
print("1-----------")
49+
position = [
50+
57.0, \
51+
0.0, \
52+
215.0, \
53+
0, \
54+
85.0, \
55+
0, \
56+
0]
57+
count = 0
58+
59+
X = round(position[0]*factor)
60+
Y = round(position[1]*factor)
61+
Z = round(position[2]*factor)
62+
RX = round(position[3]*factor)
63+
RY = round(position[4]*factor)
64+
RZ = round(position[5]*factor)
65+
joint_6 = round(position[6]*factor)
66+
print(X,Y,Z,RX,RY,RZ)
67+
piper.MotionCtrl_2(0x01, 0x00, 100, 0x00)
68+
piper.EndPoseCtrl(X,Y,Z,RX,RY,RZ)
69+
piper.GripperCtrl(abs(joint_6), 1000, 0x01, 0)
70+
time.sleep(0.01)
71+

0 commit comments

Comments
 (0)