diff --git a/CHANGELOG(ZH).MD b/CHANGELOG(ZH).MD index 5841550..90102a1 100644 --- a/CHANGELOG(ZH).MD +++ b/CHANGELOG(ZH).MD @@ -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 ============= diff --git a/CHANGELOG.MD b/CHANGELOG.MD index b4627a6..e2c1874 100644 --- a/CHANGELOG.MD +++ b/CHANGELOG.MD @@ -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 ============= diff --git a/asserts/V2/INTERFACE_V2.MD b/asserts/V2/INTERFACE_V2.MD index 809d783..5eac32b 100644 --- a/asserts/V2/INTERFACE_V2.MD +++ b/asserts/V2/INTERFACE_V2.MD @@ -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) ``` @@ -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 diff --git a/piper_sdk/demo/V2/README.MD b/piper_sdk/demo/V2/README.MD index 5a2b6b9..0c4e7c8 100644 --- a/piper_sdk/demo/V2/README.MD +++ b/piper_sdk/demo/V2/README.MD @@ -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.| @@ -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.| diff --git a/piper_sdk/demo/V2/piper_ctrl_moveJ.py b/piper_sdk/demo/V2/piper_ctrl_moveJ.py new file mode 100644 index 0000000..9dbee0b --- /dev/null +++ b/piper_sdk/demo/V2/piper_ctrl_moveJ.py @@ -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) + \ No newline at end of file diff --git a/piper_sdk/demo/V2/piper_ctrl_moveL.py b/piper_sdk/demo/V2/piper_ctrl_moveL.py new file mode 100644 index 0000000..8aeed57 --- /dev/null +++ b/piper_sdk/demo/V2/piper_ctrl_moveL.py @@ -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) + + + \ No newline at end of file diff --git a/piper_sdk/demo/V2/piper_ctrl_moveP.py b/piper_sdk/demo/V2/piper_ctrl_moveP.py new file mode 100644 index 0000000..c545dba --- /dev/null +++ b/piper_sdk/demo/V2/piper_ctrl_moveP.py @@ -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) + \ No newline at end of file diff --git a/piper_sdk/demo/V2/piper_set_joint_zero_cpv.py b/piper_sdk/demo/V2/piper_set_joint_zero_cpv.py new file mode 100644 index 0000000..316bfa0 --- /dev/null +++ b/piper_sdk/demo/V2/piper_set_joint_zero_cpv.py @@ -0,0 +1,164 @@ +#!/usr/bin/env python3 +# -*-coding:utf8-*- +""" +------------------------------------------------- + File Name: piper_set_joint_zero.py + Description: 设置关节电机零点位置 + Author: Jack + Date: 2025-10-30 + Version: 2.0 + License: MIT License +------------------------------------------------- +""" +import time +from piper_sdk import * + +# 测试代码 +if __name__ == "__main__": + piper = C_PiperInterface_V2() + piper.ConnectPort() + time.sleep(0.1) + print("设置过程输入'q'可以退出程序") + print("During setup, enter 'q' to exit the program") + print("设置零点前会对指定的电机失能,请保护好机械臂") + print("Before setting zero position, the specified motor will be disabled. Please protect the robotic arm.") + while( not piper.EnablePiper()): + time.sleep(0.01) + piper.MotionCtrl_2(0x01, 0x01, 30, 0x00) + piper.JointCtrl(0, 0, 0, 0, 0, 0) + piper.GripperCtrl(0, 1000, 0x01, 0) + mode = -1 + while True: + # 模式选择 + if mode == -1: + print("\nStep 1: 请选择设置模式(0: 指定电机; 1: 顺序设置; 2: cpv模式校准零点): ") + print("Step 1: Select setting mode (0: Single motor; 1: Sequential setting): ") + mode = input("> ") + if mode == '0': + mode = 0 + elif mode == '1': + mode = 1 + elif mode == '2': + mode = 2 + elif mode == 'q': + break + else: + mode = -1 + + # 单电机设置 + elif mode == 0: + print("\nStep 2: 输入需要设置零点的电机序号(1~7), 7代表所有电机: ") + print("Step 2: Enter motor number to set zero (1~7), 7 represents all motors: ") + motor_num = input("> ") + if motor_num == 'q': + mode = -1 + continue + try: + motor_num = int(motor_num) + if motor_num < 1 or motor_num > 7: + print("Tip: 输入超出范围") + print("Tip: Input out of range") + continue + except: + print("Tip: 请输入整数") + print("Tip: Please enter an integer") + continue + piper.DisableArm(motor_num) + print(f"\nInfo: 第{motor_num}号电机失能成功,请手动纠正电机的零点位置") + print(f"Info: Motor {motor_num} disabled successfully. Please manually adjust to zero position") + + print(f"\nStep 3: 回车设置第{motor_num}号电机零点: ") + print(f"Step 3: Press Enter to set zero for motor {motor_num}: ") + if input("(按回车继续/Press Enter) ") == 'q': + mode = -1 + continue + piper.JointConfig(motor_num, 0xAE) + piper.EnableArm(motor_num) + time.sleep(0.1) + piper.MotionCtrl_2(0x01, 0x01, 30, 0x00) + time.sleep(0.1) + piper.JointCtrl(0, 0, 0, 0, 0, 0) + print(f"\nInfo: 第{motor_num}号电机零点设置成功") + print(f"Info: Motor {motor_num} zero position set successfully") + + # 顺序设置 + elif mode == 1: + print("\nStep 2: 输入从第几号电机开始设置(1~6): ") + print("Step 2: Enter starting motor number (1~6): ") + motor_num = input("> ") + if motor_num == 'q': + mode = -1 + continue + try: + motor_num = int(motor_num) + if motor_num < 1 or motor_num > 6: + print("Tip: 输入超出范围") + print("Tip: Input out of range") + continue + except: + print("Tip: 请输入整数") + print("Tip: Please enter an integer") + continue + for i in range(motor_num, 7): + piper.DisableArm(i) + print(f"\nInfo: 第{i}号电机失能成功,请手动纠正电机的零点位置") + print(f"Info: Motor {i} disabled successfully. Please manually adjust to zero position") + + print(f"\nStep 3: 回车设置第{i}号电机零点: ") + print(f"Step 3: Press Enter to set zero for motor {i}: ") + if input("(按回车继续/Press Enter) ") == 'q': + mode = -1 + break + piper.JointConfig(i, 0xAE) + piper.EnableArm(i) + time.sleep(0.1) + piper.MotionCtrl_2(0x01, 0x01, 30, 0x00) + time.sleep(0.1) + piper.JointCtrl(0, 0, 0, 0, 0, 0) + print(f"\nInfo: 第{i}号电机零点设置成功") + print(f"Info: Motor {i} zero position set successfully") + + elif mode == 2: + print("\nStep 2: cpv模式(1: 校准j456电机; 2: 校准夹爪电机): ") + cpv = input("> ") + if cpv == 'q': + mode = -1 + continue + + elif cpv == '1': + for i in range(4, 7): + piper.DisableArm(i) + + if input("\nStep 3: j4顺时针旋转至限位,j5向上抬起至限位,j6对准中间凹槽: ") == 'q': + mode = -1 + for i in range(4, 7): + piper.EnableArm(i) + time.sleep(0.1) + piper.MotionCtrl_2(0x01, 0x01, 30, 0x00) + time.sleep(0.1) + piper.JointCtrl(0, 0, 0, 0, 0, 0) + continue + + piper.MotionCtrl_2(0x01, 0x05) + for i in range(4, 7): + id = 0x180 + i + data = [0x77, 0x65, 0x65, 0x65, 0x00, 0x00, 0x00] + piper.GetCanBus().SendCanMessage(id, data, 7) + + print("\n等待电机停止运动...") + + elif cpv == '2': + piper.GripperCtrl(0, 1000, 0x00, 0) + + if input("\nStep 3: 捏紧夹爪,使其完全闭合: ") == 'q': + mode = -1 + piper.GripperCtrl(0, 1000, 0x02, 0) + piper.GripperCtrl(0, 1000, 0x01, 0) + continue + + piper.MotionCtrl_2(0x01, 0x05) + id = 0x180 + 7 + data = [0x77, 0x65, 0x65, 0x65, 0x00, 0x00, 0x00] + piper.GetCanBus().SendCanMessage(id, data, 7) + + print("\n等待电机停止运动...") \ No newline at end of file diff --git a/piper_sdk/demo/V2/piper_set_motor_angle_limit.py b/piper_sdk/demo/V2/piper_set_motor_angle_limit.py new file mode 100644 index 0000000..c527ad4 --- /dev/null +++ b/piper_sdk/demo/V2/piper_set_motor_angle_limit.py @@ -0,0 +1,27 @@ +#!/usr/bin/env python3 +# -*-coding:utf8-*- +# 注意demo无法直接运行,需要pip安装sdk后才能运行 +# V2版本sdk +# 单独设定某个电机的关节限位 +# 注意这个指令是通过协议直接写入到驱动flash中,不可实时更新 +import time +from piper_sdk import * + +if __name__ == "__main__": + piper = C_PiperInterface_V2("can0") + piper.ConnectPort() + piper.EnableArm(7) + while( not piper.EnablePiper()): + time.sleep(0.01) + + piper.MotorAngleLimitMaxSpdSet(1, 1500, -1500) + piper.MotorAngleLimitMaxSpdSet(2, 1800, 0) + piper.MotorAngleLimitMaxSpdSet(3, 0, -1700) + piper.MotorAngleLimitMaxSpdSet(4, 1000, -1000) + piper.MotorAngleLimitMaxSpdSet(5, 700, -700) + piper.MotorAngleLimitMaxSpdSet(6, 1700, -1700) + + while True: + print(piper.GetAllMotorAngleLimitMaxSpd()) + time.sleep(0.1) + \ No newline at end of file diff --git a/piper_sdk/hardware_port/can_encapsulation_v0_4_0.py b/piper_sdk/hardware_port/can_encapsulation_v0_4_0.py index 6d224eb..cd30016 100644 --- a/piper_sdk/hardware_port/can_encapsulation_v0_4_0.py +++ b/piper_sdk/hardware_port/can_encapsulation_v0_4_0.py @@ -184,19 +184,19 @@ def ReadCanMessage(self): else: return can_bus_status - def SendCanMessage(self, arbitration_id, data): + def SendCanMessage(self, arbitration_id, data, dlc=8, is_extended_id=False): '''can transmit Args: arbitration_id (_type_): _description_ - data (_type_): _description_ + data (_type_): _description_ Defaults to 8. is_extended_id_ (bool, optional): _description_. Defaults to False. ''' message = can.Message(channel=self.channel_name, arbitration_id=arbitration_id, data=data, - dlc=8, - is_extended_id=False) + dlc=dlc, + is_extended_id=is_extended_id) if(self.is_can_bus_ok() == self.CAN_STATUS.BUS_STATE_ACTIVE): try: self.bus.send(message) diff --git a/piper_sdk/interface/piper_interface.py b/piper_sdk/interface/piper_interface.py index f1979b4..d295165 100644 --- a/piper_sdk/interface/piper_interface.py +++ b/piper_sdk/interface/piper_interface.py @@ -564,7 +564,7 @@ def CreateCanBus(self, Args: can_name: can的端口名称 - bustype: can总线类型,默认为socket can + bustype: can总线类型,默认为'socketcan',如果是串口can模块需要改为'slcan' expected_bitrate: 预期can总线的波特率 judge_flag: 是否在实例化该类时进行can端口判断,有些情况需要False ''' @@ -573,7 +573,7 @@ def CreateCanBus(self, Args: can_name: The name of the CAN port. - bustype: The type of CAN bus, default is socket CAN. + bustype: CAN bus type, the default is 'socketcan', if it is a serial port CAN module, it needs to be changed to 'slcan'. expected_bitrate: The expected bitrate for the CAN bus. judge_flag: Whether to check the CAN port during the instantiation of the class. In some cases, it should be set to False. ''' @@ -2507,7 +2507,7 @@ def ResetPiper(self): def MotionCtrl_2(self, ctrl_mode: Literal[0x00, 0x01, 0x03, 0x04, 0x07] = 0x01, - move_mode: Literal[0x00, 0x01, 0x02, 0x03, 0x04] = 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, residence_time: int = 0, @@ -2531,6 +2531,7 @@ def MotionCtrl_2(self, 0x02 MOVE L 0x03 MOVE C 0x04 MOVE M ---基于V1.5-2版本后 + 0x05 MOVE CPV ---基于V1.8-1版本后 move_spd_rate_ctrl 运动速度百分比 uint8 数值范围0~100 is_mit_mode: mit模式 uint8 @@ -2561,6 +2562,7 @@ def MotionCtrl_2(self, 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 (int): The movement speed percentage (0-100). is_mit_mode (int): The MIT mode. 0x00: Position-velocity mode @@ -2584,7 +2586,7 @@ def MotionCtrl_2(self, def ModeCtrl(self, 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): ''' @@ -2602,6 +2604,8 @@ def ModeCtrl(self, 0x01 MOVE J 0x02 MOVE L 0x03 MOVE C + 0x04 MOVE M ---基于V1.5-2版本后 + 0x05 MOVE CPV ---基于V1.8-1版本后 move_spd_rate_ctrl 运动速度百分比 uint8 数值范围0~100 is_mit_mode: mit模式 uint8 @@ -2621,6 +2625,8 @@ def ModeCtrl(self, 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 (int): The movement speed percentage (0-100). is_mit_mode (int): The MIT mode. 0x00: Position-velocity mode diff --git a/piper_sdk/interface/piper_interface_v2.py b/piper_sdk/interface/piper_interface_v2.py index 5698844..47f4164 100644 --- a/piper_sdk/interface/piper_interface_v2.py +++ b/piper_sdk/interface/piper_interface_v2.py @@ -564,7 +564,7 @@ def CreateCanBus(self, Args: can_name: can的端口名称 - bustype: can总线类型,默认为socket can + bustype: can总线类型,默认为'socketcan',如果是串口can模块需要改为'slcan' expected_bitrate: 预期can总线的波特率 judge_flag: 是否在实例化该类时进行can端口判断,有些情况需要False ''' @@ -573,7 +573,7 @@ def CreateCanBus(self, Args: can_name: The name of the CAN port. - bustype: The type of CAN bus, default is socket CAN. + bustype: CAN bus type, the default is 'socketcan', if it is a serial port CAN module, it needs to be changed to 'slcan'. expected_bitrate: The expected bitrate for the CAN bus. judge_flag: Whether to check the CAN port during the instantiation of the class. In some cases, it should be set to False. ''' @@ -2507,7 +2507,7 @@ def ResetPiper(self): def MotionCtrl_2(self, ctrl_mode: Literal[0x00, 0x01, 0x03, 0x04, 0x07] = 0x01, - move_mode: Literal[0x00, 0x01, 0x02, 0x03, 0x04] = 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, residence_time: int = 0, @@ -2531,6 +2531,7 @@ def MotionCtrl_2(self, 0x02 MOVE L 0x03 MOVE C 0x04 MOVE M ---基于V1.5-2版本后 + 0x05 MOVE CPV ---基于V1.8-1版本后 move_spd_rate_ctrl 运动速度百分比 uint8 数值范围0~100 is_mit_mode: mit模式 uint8 @@ -2561,6 +2562,7 @@ def MotionCtrl_2(self, 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 (int): The movement speed percentage (0-100). is_mit_mode (int): The MIT mode. 0x00: Position-velocity mode @@ -2584,7 +2586,7 @@ def MotionCtrl_2(self, def ModeCtrl(self, 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): ''' @@ -2602,6 +2604,8 @@ def ModeCtrl(self, 0x01 MOVE J 0x02 MOVE L 0x03 MOVE C + 0x04 MOVE M ---基于V1.5-2版本后 + 0x05 MOVE CPV ---基于V1.8-1版本后 move_spd_rate_ctrl 运动速度百分比 uint8 数值范围0~100 is_mit_mode: mit模式 uint8 @@ -2621,6 +2625,8 @@ def ModeCtrl(self, 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 (int): The movement speed percentage (0-100). is_mit_mode (int): The MIT mode. 0x00: Position-velocity mode diff --git a/piper_sdk/piper_msgs/msg_v2/transmit/arm_motion_ctrl_2.py b/piper_sdk/piper_msgs/msg_v2/transmit/arm_motion_ctrl_2.py index b0f455a..1538c58 100644 --- a/piper_sdk/piper_msgs/msg_v2/transmit/arm_motion_ctrl_2.py +++ b/piper_sdk/piper_msgs/msg_v2/transmit/arm_motion_ctrl_2.py @@ -34,6 +34,7 @@ class ArmMsgMotionCtrl_2(): 0x02 MOVE L 0x03 MOVE C 0x04 MOVE M ---基于V1.5-2版本后 + 0x05 MOVE CPV ---基于V1.8-1版本后 Byte 2: 运动速度百分比 uint8 0~100 Byte 3: mit模式 uint8 0x00 位置速度模式 @@ -76,6 +77,7 @@ class ArmMsgMotionCtrl_2(): 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 Byte 2 speed_percentage: uint8, movement speed as a percentage. Range: 0~100. @@ -96,7 +98,7 @@ class ArmMsgMotionCtrl_2(): ''' def __init__(self, ctrl_mode: Literal[0x00, 0x01, 0x03, 0x04, 0x07] = 0x01, - move_mode: Literal[0x00, 0x01, 0x02, 0x03, 0x04] = 0x01, + move_mode: Literal[0x00, 0x01, 0x02, 0x03, 0x04, 0x05] = 0x01, move_spd_rate_ctrl: int = 50, mit_mode: Literal[0x00, 0xAD, 0xFF] = 0x00, residence_time: int = 0, @@ -104,8 +106,8 @@ def __init__(self, # 检查是否在有效范围内 if ctrl_mode not in [0x00, 0x01, 0x03, 0x04, 0x07]: raise ValueError(f"'ctrl_mode' Value {ctrl_mode} out of range [0x00, 0x01, 0x02, 0x03, 0x04, 0x07]") - if move_mode not in [0x00, 0x01, 0x02, 0x03, 0x04]: - raise ValueError(f"'move_mode' Value {move_mode} out of range [0x00, 0x01, 0x02, 0x03, 0x04]") + if move_mode not in [0x00, 0x01, 0x02, 0x03, 0x04, 0x05]: + raise ValueError(f"'move_mode' Value {move_mode} out of range [0x00, 0x01, 0x02, 0x03, 0x04, 0x05]") if not (0 <= move_spd_rate_ctrl <= 100): raise ValueError(f"'move_spd_rate_ctrl' Value {move_spd_rate_ctrl} out of range 0-100") if mit_mode not in [0x00, 0xAD, 0xFF]: diff --git a/piper_sdk/version.py b/piper_sdk/version.py index 1a35ff0..399f4cb 100644 --- a/piper_sdk/version.py +++ b/piper_sdk/version.py @@ -15,7 +15,8 @@ class PiperSDKVersion(Enum): PIPER_SDK_VERSION_0_4_3 = '0.4.3' PIPER_SDK_VERSION_0_5_0 = '0.5.0' PIPER_SDK_VERSION_0_6_0 = '0.6.0' - PIPER_SDK_CURRENT_VERSION = PIPER_SDK_VERSION_0_6_0 + PIPER_SDK_VERSION_0_6_1 = '0.6.1' + PIPER_SDK_CURRENT_VERSION = PIPER_SDK_VERSION_0_6_1 PIPER_SDK_VERSION_UNKNOWN = 'unknown' def __str__(self): return f"{self.name} ({self.value})" diff --git a/setup.py b/setup.py index 1575d6f..3ae3a70 100644 --- a/setup.py +++ b/setup.py @@ -6,7 +6,7 @@ setup( name='piper_sdk', - version='0.6.0', + version='0.6.1', setup_requires=['setuptools>=40.0'], long_description=open(os.path.join(here, 'DESCRIPTION.MD'), encoding='utf-8').read(), long_description_content_type='text/markdown',