Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
27 changes: 27 additions & 0 deletions CHANGELOG(ZH).MD
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,33 @@
[Click to switch EN](CHANGELOG.MD)
=============

Version 0.6.1
=============

特性
--------

- ✨ feat(can_encapsulation): 为`SendCanMessage`增加`dlc`以及`is_extended_id`参数
- ✨ feat(interface,piper_msgs): 增加CPV模式选择以及注释说明
- 可以通过`ModeCtrl(0x01, 0x05)`来切换到CPV模式

Bug修复
---------

其它
---------

- 🧪 test(demo): 增加单独设定某个电机的关节限位的demo,`piper_set_motor_angle_limit.py`
- 🧪 test(demo): 增加cpv模式下控制机械臂设置零点demo,`piper_set_joint_zero_cpv.py`
- 📃 docs(interface): 修改CreateCanBus函数中bustype参数注释说明
- 修改CreateCanBus函数中bustype有关的注释说明,说明预期参数为'socketcan'或'slcan'
- 🧪 test(demo): 增加moveJ、moveL、moveP三个demo;同步demo中的README
- 增加`piper_ctrl_moveJ.py`的demo,与`piper_ctrl_joint.py`内容相同;
- 增加`piper_ctrl_moveL.py`的demo,效果为机械臂绘画正方形;
- 增加`piper_ctrl_moveP.py`的demo,与`piper_ctrl_end_pose.py`内容相同;
- 同步demo的README内容。

Version 0.6.0
=============

Expand Down
28 changes: 28 additions & 0 deletions CHANGELOG.MD
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,34 @@
[Click to switch ZH](CHANGELOG(ZH).MD)
=============

Version 0.6.1
=============

Features
--------

- ✨ feat(can_encapsulation): Adds `dlc` and `is_extended_id` parameters to `SendCanMessage`
- ✨ feat(interface,piper_msgs): Adds CPV mode selection and comments
- CPV mode can be switched using `ModeCtrl(0x01, 0x05)`

Bug Fixes
---------

None

Miscellaneous
---------

- 🧪 test(demo): Added a demo for setting the joint limit of a single motor, `piper_set_motor_angle_limit.py`
- 🧪 test(demo): Added a demo for setting the zero point of the robotic arm in CPV mode, `piper_set_joint_zero_cpv.py`
- 📃 docs(interface): Modified the comment for the bustype parameter in the CreateCanBus function
- Modified the comments related to bustype in the `CreateCanBus` function to specify that the expected parameter is `'socketcan'` or `'slcan'`.
- 🧪 test(demo): Added three demos: moveJ, moveL, and moveP; synchronized the README in the demos.
- Added a demo for `piper_ctrl_moveJ.py`, with the same content as `piper_ctrl_joint.py`;
- Added a demo for `piper_ctrl_moveL.py`, which shows a robotic arm drawing a square;
- Added a demo for `piper_ctrl_moveP.py`, with the same content as `piper_ctrl_end_pose.py`;
- Synchronized the README content in the demos.

Version 0.6.0
=============

Expand Down
4 changes: 3 additions & 1 deletion asserts/V2/INTERFACE_V2.MD
Original file line number Diff line number Diff line change
Expand Up @@ -130,7 +130,7 @@ The robot will immediately lose power and fall down, clearing all errors and int

```python
def ModeCtrl(ctrl_mode: Literal[0x00, 0x01] = 0x01,
move_mode: Literal[0x00, 0x01, 0x02, 0x03] = 0x01,
move_mode: Literal[0x00, 0x01, 0x02, 0x03, 0x04, 0x05] = 0x01,
move_spd_rate_ctrl: int = 50,
is_mit_mode: Literal[0x00, 0xAD, 0xFF] = 0x00)
```
Expand All @@ -147,6 +147,8 @@ Parameters:
- 0x01: MOVE J (Joint)
- 0x02: MOVE L (Linear)
- 0x03: MOVE C (Circular)
- 0x04: MOVE M (MIT) ---- Based on version V1.5-2 and later
- 0x05: MOVE CPV ---- Based on version V1.8-1 and later
- `move_spd_rate_ctrl`: Movement speed percentage (0-100)
- `is_mit_mode`:
- 0x00: Position-velocity mode
Expand Down
14 changes: 14 additions & 0 deletions piper_sdk/demo/V2/README.MD
Original file line number Diff line number Diff line change
Expand Up @@ -33,9 +33,14 @@ Instructions for activating the CAN module [can README](../../asserts/can_config
|[`piper_ctrl_disable.py`](./piper_ctrl_disable.py)|Disable the robotic arm.|
|[`piper_ctrl_enable.py`](./piper_ctrl_enable.py)|Enable the robotic arm.|
|[`piper_ctrl_end_pose.py`](./piper_ctrl_end_pose.py)|Control the end-effector of the robotic arm.|
|[`piper_ctrl_go_zero.py`](./piper_ctrl_go_zero.py)|Control the robotic arm to the zero position.|
|[`piper_ctrl_gripper.py`](./piper_ctrl_gripper.py)|Control the robotic arm gripper.|
|[`piper_ctrl_joint.py`](./piper_ctrl_joint.py)|Control the robotic arm joints.|
|[`piper_ctrl_line.py`](./piper_ctrl_line.py)|Control the robotic arm in line motion mode.|
|[`piper_ctrl_moveC.py`](./piper_ctrl_moveC.py)|Set the robotic arm to circular motion mode.|
|[`piper_ctrl_moveJ.py`](./piper_ctrl_moveJ.py)|Control the joint movement of the robotic arm.|
|[`piper_ctrl_moveL.py`](./piper_ctrl_moveL.py)|Control the robotic arm to draw a square on the XOY plane.|
|[`piper_ctrl_moveP.py`](./piper_ctrl_moveP.py)|Control the movement of the robotic arm's end effector.|
|[`piper_ctrl_reset.py`](./piper_ctrl_reset.py)|Reset the robotic arm. This must be executed once after setting it to teaching mode.|
|[`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.|
|[`piper_read_all_fps.py`](./piper_read_all_fps.py)|Read the frequency of specified robotic arm data.|
Expand All @@ -50,13 +55,22 @@ Instructions for activating the CAN module [can README](../../asserts/can_config
|[`piper_read_joint_ctrl.py`](./piper_read_joint_ctrl.py)|Read and print joint control messages.|
|[`piper_read_joint_state.py`](./piper_read_joint_state.py)|Read and print joint state messages.|
|[`piper_read_low_msg.py`](./piper_read_low_msg.py)|Read low-speed messages from the robotic arm.|
|[`piper_read_mode_ctrl_canid_151.py`](./piper_read_mode_ctrl_canid_151.py)|Read the current mode control message from CAN ID 151.|
|[`piper_read_mode_ctrl.py`](./piper_read_mode_ctrl.py)|Read the current mode control message from CAN ID 151.|
|[`piper_read_resp_instruction.py`](./piper_read_resp_instruction.py)|Read the current instruction of the robotic arm.|
|[`piper_read_status.py`](./piper_read_status.py)|Read the current status of the robotic arm.|
|[`piper_read_tcp_pose.py`](./piper_read_tcp_pose.py)|Read the tool center point (TCP) pose.|
|[`piper_read_version.py`](./piper_read_version.py)|Read the software version of each module in the robotic arm SDK.|
|[`piper_set_can.py`](./piper_set_can.py)|Set the CAN bus parameters for the robotic arm.|
|[`piper_set_gripper_zero.py`](./piper_set_gripper_zero.py)|Set the zero position of the robotic arm gripper.|
|[`piper_set_init_default.py`](./piper_set_init_default.py)|Set all joint limits, maximum joint speeds, and joint accelerations to default values.|
|[`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).|
|[`piper_set_joint_zero.py`](./piper_set_joint_zero.py)|Set the zero position of the robotic arm joints.|
|[`piper_set_load.py`](./piper_set_load.py)|Set the end load parameters for the robotic arm.|
|[`piper_set_log_level.py`](./piper_set_log_level.py)|Set the log level for the robotic arm SDK.|
|[`piper_set_master.py`](./piper_set_master.py)|Set the robotic arm as the master arm.|
|[`piper_set_mit.py`](./piper_set_mit.py)|Set the robotic arm to MIT mode, which provides the fastest response.|
|[`piper_set_motor_angle_limit.py`](./piper_set_motor_angle_limit.py)|Set the angle limits for individual joint motors.|
|[`piper_set_motor_max_acc_limit.py`](./piper_set_motor_max_acc_limit.py)|Set the maximum acceleration limit for individual joint motors.|
|[`piper_set_sdk_param.py`](./piper_set_sdk_param.py)|Set SDK parameters for joint and gripper limits.|
|[`piper_set_slave.py`](./piper_set_slave.py)|Set the robotic arm as the slave arm.|
Expand Down
43 changes: 43 additions & 0 deletions piper_sdk/demo/V2/piper_ctrl_moveJ.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
#!/usr/bin/env python3
# -*-coding:utf8-*-
# 注意demo无法直接运行,需要pip安装sdk后才能运行
import time
from piper_sdk import *

if __name__ == "__main__":
piper = C_PiperInterface_V2("can0")
piper.ConnectPort()
while( not piper.EnablePiper()):
time.sleep(0.01)
piper.GripperCtrl(0,1000,0x01, 0)
factor = 57295.7795 #1000*180/3.1415926
position = [0,0,0,0,0,0,0]
count = 0
while True:
count = count + 1
# print(count)
if(count == 0):
print("1-----------")
position = [0,0,0,0,0,0,0]
elif(count == 300):
print("2-----------")
position = [0.2,0.2,-0.2,0.3,-0.2,0.5,0.08]
elif(count == 600):
print("1-----------")
position = [0,0,0,0,0,0,0]
count = 0

joint_0 = round(position[0]*factor)
joint_1 = round(position[1]*factor)
joint_2 = round(position[2]*factor)
joint_3 = round(position[3]*factor)
joint_4 = round(position[4]*factor)
joint_5 = round(position[5]*factor)
joint_6 = round(position[6]*1000*1000)
piper.MotionCtrl_2(0x01, 0x01, 100, 0x00)
piper.JointCtrl(joint_0, joint_1, joint_2, joint_3, joint_4, joint_5)
piper.GripperCtrl(abs(joint_6), 1000, 0x01, 0)
print(piper.GetArmStatus())
print(position)
time.sleep(0.005)

38 changes: 38 additions & 0 deletions piper_sdk/demo/V2/piper_ctrl_moveL.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
#!/usr/bin/env python3
# -*-coding:utf8-*-
# 注意demo无法直接运行,需要pip安装sdk后才能运行
# piper机械臂直线模式demo
# 注意机械臂工作空间内不要有障碍
import time
from piper_sdk import *

if __name__ == "__main__":
piper = C_PiperInterface_V2("can0")
piper.ConnectPort()
while( not piper.EnablePiper()):
time.sleep(0.01)

# 在XOY平面上画正方形
# 切换至MOVEP模式,移动到初始位置
piper.MotionCtrl_2(0x01, 0x00, 100, 0x00)
piper.EndPoseCtrl(150000, -50000, 150000, -179900, 0, -179900)
time.sleep(2)

# 切换至MOVEL模式
piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
piper.EndPoseCtrl(150000, 50000, 150000, -179900, 0, -179900)
time.sleep(2)

piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
piper.EndPoseCtrl(250000, 50000, 150000, -179900, 0, -179900)
time.sleep(2)

piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
piper.EndPoseCtrl(250000, -50000, 150000, -179900, 0, -179900)
time.sleep(2)

piper.MotionCtrl_2(0x01, 0x02, 100, 0x00)
piper.EndPoseCtrl(150000, -50000, 150000, -179900, 0, -179900)



71 changes: 71 additions & 0 deletions piper_sdk/demo/V2/piper_ctrl_moveP.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
#!/usr/bin/env python3
# -*-coding:utf8-*-
# 注意demo无法直接运行,需要pip安装sdk后才能运行
import time
from piper_sdk import *

if __name__ == "__main__":
piper = C_PiperInterface_V2("can0")
piper.ConnectPort()
while( not piper.EnablePiper()):
time.sleep(0.01)
piper.GripperCtrl(0,1000,0x01, 0)
factor = 1000
position = [
57.0, \
0.0, \
215.0, \
0, \
85.0, \
0, \
0]

count = 0
while True:
print(piper.GetArmEndPoseMsgs())
count = count + 1
if(count == 0):
print("1-----------")
position = [
57.0, \
0.0, \
215.0, \
0, \
85.0, \
0, \
0]
elif(count == 200):
print("2-----------")
position = [
57.0, \
0.0, \
260.0, \
0, \
85.0, \
0, \
0]
elif(count == 400):
print("1-----------")
position = [
57.0, \
0.0, \
215.0, \
0, \
85.0, \
0, \
0]
count = 0

X = round(position[0]*factor)
Y = round(position[1]*factor)
Z = round(position[2]*factor)
RX = round(position[3]*factor)
RY = round(position[4]*factor)
RZ = round(position[5]*factor)
joint_6 = round(position[6]*factor)
print(X,Y,Z,RX,RY,RZ)
piper.MotionCtrl_2(0x01, 0x00, 100, 0x00)
piper.EndPoseCtrl(X,Y,Z,RX,RY,RZ)
piper.GripperCtrl(abs(joint_6), 1000, 0x01, 0)
time.sleep(0.01)

Loading