Skip to content

Commit 9cb79c2

Browse files
committed
[FEAT]增加interface版本反馈函数,protocol版本反馈函数,sdk版本反馈函数;[FEAT]增加sdk软件关节角度限位(弧度)和夹爪行程限幅(米);[BUG]修复高速信息反馈的电流反馈单位为有符号数据以及打印数据错误赋值问题
1 parent 2e353a5 commit 9cb79c2

16 files changed

+466
-161
lines changed

__init__.py

+4-2
Original file line numberDiff line numberDiff line change
@@ -2,15 +2,16 @@
22
from .hardware_port.can_encapsulation import C_STD_CAN
33
from .base.piper_base import C_PiperBase
44
from .monitor.fps import C_FPSCounter
5+
from .protocol.piper_protocol_base import C_PiperParserBase
56
from .piper_msgs.msg_v1 import *
67
from .protocol.protocol_v1 import *
78
from .piper_msgs.msg_v2 import *
89
from .protocol.protocol_v2 import *
910
from .kinematics.piper_fk import C_PiperForwardKinematics
10-
from .protocol.piper_protocol_base import C_PiperParserBase
1111
from .interface.piper_interface import C_PiperInterface
1212
from .interface.piper_interface_v1 import C_PiperInterface_V1
1313
from .interface.piper_interface_v2 import C_PiperInterface_V2
14+
from .version import PiperSDKVersion
1415

1516
__all__ = [
1617
'C_PiperParserBase',
@@ -20,5 +21,6 @@
2021
'C_PiperBase',
2122
'C_PiperInterface',
2223
'C_PiperInterface_V1',
23-
'C_PiperInterface_V2'
24+
'C_PiperInterface_V2',
25+
'PiperSDKVersion'
2426
]

demo/V1/read_version.py

+17
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
#!/usr/bin/env python3
2+
# -*-coding:utf8-*-
3+
# 注意demo无法直接运行,需要pip安装sdk后才能运行
4+
5+
from piper_sdk import *
6+
7+
# 测试代码
8+
if __name__ == "__main__":
9+
piper = C_PiperInterface_V1()
10+
piper.ConnectPort(piper_init=False, start_thread=False)
11+
print(f'=====>> Piper Current Interface Version is {piper.GetCurrentInterfaceVersion()} <<=====')
12+
print(f'=====>> Piper Current Interface Version is {piper.GetCurrentInterfaceVersion().value} <<=====')
13+
print(f'=====>> Piper Current Protocol Version is {piper.GetCurrentProtocolVersion()} <<=====')
14+
print(f'=====>> Piper Current Protocol Version is {piper.GetCurrentProtocolVersion().value} <<=====')
15+
print(f'=====>> Piper Current SDK Version is {piper.GetCurrentSDKVersion()} <<=====')
16+
print(f'=====>> Piper Current SDK Version is {piper.GetCurrentSDKVersion().value} <<=====')
17+

demo/V2/read_version.py

+16
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,16 @@
1+
#!/usr/bin/env python3
2+
# -*-coding:utf8-*-
3+
# 注意demo无法直接运行,需要pip安装sdk后才能运行
4+
5+
from piper_sdk import *
6+
7+
# 测试代码
8+
if __name__ == "__main__":
9+
piper = C_PiperInterface_V2()
10+
piper.ConnectPort(piper_init=False, start_thread=False)
11+
print(f'=====>> Piper Current Interface Version is {piper.GetCurrentInterfaceVersion()} <<=====')
12+
print(f'=====>> Piper Current Interface Version is {piper.GetCurrentInterfaceVersion().value} <<=====')
13+
print(f'=====>> Piper Current Protocol Version is {piper.GetCurrentProtocolVersion()} <<=====')
14+
print(f'=====>> Piper Current Protocol Version is {piper.GetCurrentProtocolVersion().value} <<=====')
15+
print(f'=====>> Piper Current SDK Version is {piper.GetCurrentSDKVersion()} <<=====')
16+
print(f'=====>> Piper Current SDK Version is {piper.GetCurrentSDKVersion().value} <<=====')

interface/interface_version.py

+19
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,19 @@
1+
#!/usr/bin/env python3
2+
# -*-coding:utf8-*-
3+
4+
from enum import Enum, auto
5+
6+
class InterfaceVersion(Enum):
7+
'''
8+
Interface版本枚举
9+
'''
10+
'''
11+
Interface Version Enumeration.
12+
'''
13+
INTERFACE_V1 = auto()
14+
INTERFACE_V2 = auto()
15+
INTERFACE_UNKNOWN = auto()
16+
def __str__(self):
17+
return f"{self.name} (0x{self.value:X})"
18+
def __repr__(self):
19+
return f"{self.name}: 0x{self.value:X}"

interface/piper_interface.py

+113-58
Large diffs are not rendered by default.

interface/piper_interface_v1.py

+113-58
Large diffs are not rendered by default.

interface/piper_interface_v2.py

+46-23
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,8 @@
1919
from ..piper_msgs.msg_v2 import *
2020
from ..kinematics import *
2121
from ..monitor import *
22+
from ..version import PiperSDKVersion
23+
from .interface_version import InterfaceVersion
2224

2325
class C_PiperInterface_V2():
2426
'''
@@ -492,21 +494,17 @@ def get_instance(cls, can_name="can0", judge_flag=True, can_auto_init=True):
492494
"""获取实例,简化调用"""
493495
return cls(can_name, judge_flag, can_auto_init)
494496

495-
def ConnectPort(self, can_init=False):
496-
'''
497-
连接端口开启线程处理数据
498-
499-
开启读取can端口读取线程
500-
发送一次查询关节电机最大角度速度指令
501-
和一次查询关节电机最大加速度限制指令
502-
'''
497+
def ConnectPort(self,
498+
can_init :bool = False,
499+
piper_init :bool = True,
500+
start_thread :bool = True):
503501
'''
504502
Starts a thread to process data from the connected CAN port.
505-
506-
This function does the following:
507-
Starts a thread to read data from the CAN port.
508-
Sends a query for the joint motor's maximum angle and speed.
509-
Sends a query for the joint motor's maximum acceleration limit.
503+
504+
Args:
505+
can_init(bool): can port init flag, Behind you using DisconnectPort(), you should set it True.
506+
piper_init(bool): Execute the robot arm initialization function
507+
start_thread(bool): Start the reading thread
510508
'''
511509
if(can_init or not self.__connected):
512510
self.__arm_can.Init()
@@ -537,16 +535,16 @@ def CanMonitor():
537535
break
538536
self.__can_monitor_stop_event.wait(0.01)
539537
try:
540-
if not self.__can_deal_th or not self.__can_deal_th.is_alive():
541-
self.__can_deal_th = threading.Thread(target=ReadCan, daemon=True)
542-
self.__can_deal_th.start()
543-
if not self.__can_monitor_th or not self.__can_monitor_th.is_alive():
544-
self.__can_monitor_th = threading.Thread(target=CanMonitor, daemon=True)
545-
self.__can_monitor_th.start()
546-
self.__fps_counter.start()
547-
self.SearchAllMotorMaxAngleSpd()
548-
self.SearchAllMotorMaxAccLimit()
549-
self.SearchPiperFirmwareVersion()
538+
if start_thread:
539+
if not self.__can_deal_th or not self.__can_deal_th.is_alive():
540+
self.__can_deal_th = threading.Thread(target=ReadCan, daemon=True)
541+
self.__can_deal_th.start()
542+
if not self.__can_monitor_th or not self.__can_monitor_th.is_alive():
543+
self.__can_monitor_th = threading.Thread(target=CanMonitor, daemon=True)
544+
self.__can_monitor_th.start()
545+
self.__fps_counter.start()
546+
if piper_init:
547+
self.PiperInit()
550548
except Exception as e:
551549
print(f"[ERROR] 线程启动失败: {e}")
552550
self.__connected = False # 回滚状态
@@ -579,6 +577,16 @@ def DisconnectPort(self, thread_timeout=0.1):
579577
except Exception as e:
580578
print(f"[ERROR] 关闭 CAN 端口时发生异常: {e}")
581579

580+
def PiperInit(self):
581+
'''
582+
发送查询关节电机最大角度速度指令
583+
发送查询关节电机最大加速度限制指令
584+
发送查询机械臂固件指令
585+
'''
586+
self.SearchAllMotorMaxAngleSpd()
587+
self.SearchAllMotorMaxAccLimit()
588+
self.SearchPiperFirmwareVersion()
589+
582590
def ParseCANFrame(self, rx_message: Optional[can.Message]):
583591
'''can协议解析函数
584592
@@ -627,6 +635,21 @@ def ParseCANFrame(self, rx_message: Optional[can.Message]):
627635
# '''
628636
# pass
629637
# 获取反馈值------------------------------------------------------------------------------------------------------
638+
def GetCurrentInterfaceVersion(self):
639+
return InterfaceVersion.INTERFACE_V2
640+
641+
def GetCurrentSDKVersion(self):
642+
'''
643+
return piper_sdk current version
644+
'''
645+
return PiperSDKVersion.PIPER_SDK_CURRENT_VERSION
646+
647+
def GetCurrentProtocolVersion(self):
648+
'''
649+
return piper_sdk current prptocol version
650+
'''
651+
return self.__parser.GetParserProtocolVersion()
652+
630653
def GetCanFps(self):
631654
'''
632655
获取机械臂can模块帧率

monitor/__init__.py

-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,6 @@
11

22
from .fps import C_FPSCounter
33

4-
# 导入 hardware_port 子模块
5-
64
__all__ = [
75
'C_FPSCounter'
86
]

piper_msgs/msg_v1/feedback/arm_high_spd_feedback.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ def cal_effort(self, current: int = None)-> float:
9797
def __str__(self):
9898
return (f"ArmHighSpdFeedback(\n"
9999
f" can_id: {hex(self.can_id)},\n"
100-
f" motor_speed: {self.motor_speed}, {self.current*0.001} rad/s,\n"
100+
f" motor_speed: {self.motor_speed}, {self.motor_speed*0.001} rad/s,\n"
101101
f" current: {self.current}, {self.current*0.001}A\n"
102102
f" pos: {self.pos} rad\n"
103103
f" effort: {self.effort}, {self.current*0.001}N/m\n"

piper_msgs/msg_v2/feedback/arm_high_spd_feedback.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ def cal_effort(self, current: int = None)-> float:
9898
def __str__(self):
9999
return (f"ArmHighSpdFeedback(\n"
100100
f" can_id: {hex(self.can_id)},\n"
101-
f" motor_speed: {self.motor_speed}, {self.current*0.001} rad/s,\n"
101+
f" motor_speed: {self.motor_speed}, {self.motor_speed*0.001} rad/s,\n"
102102
f" current: {self.current}, {self.current*0.001}A\n"
103103
f" pos: {self.pos} rad\n"
104104
f" effort: {self.effort}, {self.effort*0.001}N/m\n"

piper_param/__init__.py

+7
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
2+
from .piper_param_manager import C_PiperParamManager
3+
4+
__all__ = [
5+
'C_PiperParamManager'
6+
]
7+

piper_param/piper_param_manager.py

+99
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
import copy
2+
from typing_extensions import (
3+
Literal,
4+
)
5+
from ..version import PiperSDKVersion
6+
7+
class C_PiperParamManager():
8+
_instance = None
9+
10+
def __new__(cls, *args, **kwargs):
11+
if cls._instance is None:
12+
cls._instance = super().__new__(cls)
13+
return cls._instance
14+
15+
def __init__(self) -> None:
16+
'''
17+
|joint_name| limit(rad) | limit(angle) |
18+
|----------| ---------- | ---------- |
19+
|joint1 | [-2.618, 2.618] | [-150.0, 150.0] |
20+
|joint2 | [0, 3.14] | [0, 180.0] |
21+
|joint3 | [-2.967, 0] | [-170, 0] |
22+
|joint4 | [-1.745, 1.745] | [-100.0, 100.0] |
23+
|joint5 | [-1.22, 1.22] | [-70.0, 70.0] |
24+
|joint6 | [-2.0944, 2.0944]| [-120.0, 120.0] |
25+
'''
26+
if not hasattr(self, "PIPER_PARAM"):
27+
self.__PIPER_PARAM_ORIGIN = {
28+
"joint_limit":{
29+
"j1": [-2.618, 2.618],
30+
"j2": [0, 3.14],
31+
"j3": [-2.967, 0],
32+
"j4": [-1.745, 1.745],
33+
"j5": [-1.22, 1.22],
34+
"j6": [-2.0944, 2.0944],
35+
},
36+
"gripper_range": [0.0, 0.07],
37+
"piper_sdk_version": PiperSDKVersion.PIPER_SDK_CURRENT_VERSION
38+
}
39+
self.PIPER_PARAM = copy.deepcopy(self.__PIPER_PARAM_ORIGIN)
40+
41+
def ResetDefaultParam(self):
42+
self.PIPER_PARAM.update(copy.deepcopy(self.__PIPER_PARAM_ORIGIN))
43+
44+
def GetPiperParamOrigin(self):
45+
return copy.deepcopy(self.__PIPER_PARAM_ORIGIN)
46+
47+
def GetCurrentPiperParam(self):
48+
return copy.deepcopy(self.PIPER_PARAM)
49+
50+
def GetCurrentPiperSDKVersion(self):
51+
return self.PIPER_PARAM["piper_sdk_version"]
52+
53+
def GetJointLimitParam(self,
54+
joint_name: Literal["j1", "j2", "j3", "j4", "j5", "j6"]):
55+
if joint_name not in ["j1", "j2", "j3", "j4", "j5", "j6"]:
56+
raise ValueError(f'"joint_name" Value {joint_name} is not in ["j1", "j2", "j3", "j4", "j5", "j6"]')
57+
return self.PIPER_PARAM["joint_limit"][joint_name][0], self.PIPER_PARAM["joint_limit"][joint_name][1]
58+
59+
def GetGripperRangeParam(self):
60+
return self.PIPER_PARAM["gripper_range"][0], self.PIPER_PARAM["gripper_range"][1]
61+
62+
def SetJointLimitParam(self,
63+
joint_name: Literal["j1", "j2", "j3", "j4", "j5", "j6"],
64+
min_val: float,
65+
max_val: float):
66+
if joint_name not in ["j1", "j2", "j3", "j4", "j5", "j6"]:
67+
raise ValueError(f'"joint_name" Value {joint_name} is not in ["j1", "j2", "j3", "j4", "j5", "j6"]')
68+
if max_val - min_val < 0:
69+
raise ValueError(f'max_val should be greater than min_val.')
70+
self.PIPER_PARAM["joint_limit"][joint_name] = [min_val, max_val]
71+
72+
def SetGripperRangeParam(self,
73+
min_val: float,
74+
max_val: float):
75+
if max_val - min_val < 0:
76+
raise ValueError(f'max_val should be greater than min_val.')
77+
self.PIPER_PARAM["gripper_range"] = [min_val, max_val]
78+
79+
# a = C_PiperParamManager()
80+
# print( a.GetCurrentPiperParam())
81+
# a.SetGripperRangeParam(-20000,30000)
82+
# a.SetJointLimitParam("j1",-20000,30000)
83+
# print( a.GetCurrentPiperParam())
84+
# a.ResetDefaultParam()
85+
# print( a.GetCurrentPiperParam())
86+
87+
# # ✅ 测试单例模式
88+
# manager1 = C_PiperParamManager()
89+
# manager2 = C_PiperParamManager()
90+
91+
# print(manager1 is manager2) # ✅ True,确保是同一个实例
92+
93+
# # 修改 manager1 的参数
94+
# manager1.SetGripperRangeParam(-500, 500)
95+
# print(manager2.GetCurrentPiperParam()) # ✅ manager2 也受影响,说明是同一个实例
96+
97+
# # 复位参数
98+
# manager2.ResetDefaultParam()
99+
# print(manager1.GetCurrentPiperParam()) # ✅ manager1 也被复位,单例模式生效!

protocol/piper_protocol_base.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -24,8 +24,9 @@ class ProtocolVersion(Enum):
2424
'''
2525
Protocol Version Enumeration, needs to be specified in the derived class.
2626
'''
27-
ARM_PROTOCOL_UNKNOWN = auto()
2827
ARM_PROROCOL_V1 = auto()
28+
ARM_PROROCOL_V2 = auto()
29+
ARM_PROTOCOL_UNKNOWN = auto()
2930
def __str__(self):
3031
return f"{self.name} (0x{self.value:X})"
3132
def __repr__(self):

protocol/protocol_v1/piper_protocol_v1.py

+6-6
Original file line numberDiff line numberDiff line change
@@ -122,37 +122,37 @@ def DecodeMessage(self, rx_can_frame: Optional[can.Message], msg:PiperMessage):
122122
msg.type_ = ArmMessageMapping.get_mapping(can_id=can_id)
123123
msg.arm_high_spd_feedback_1.can_id = can_id
124124
msg.arm_high_spd_feedback_1.motor_speed = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,0,2))
125-
msg.arm_high_spd_feedback_1.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4),False)
125+
msg.arm_high_spd_feedback_1.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4))
126126
msg.arm_high_spd_feedback_1.pos = self.ConvertToNegative_32bit(self.ConvertBytesToInt(can_data,4,8))
127127
elif(can_id == CanIDPiper.ARM_INFO_HIGH_SPD_FEEDBACK_2.value):
128128
msg.type_ = ArmMessageMapping.get_mapping(can_id=can_id)
129129
msg.arm_high_spd_feedback_2.can_id = can_id
130130
msg.arm_high_spd_feedback_2.motor_speed = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,0,2))
131-
msg.arm_high_spd_feedback_2.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4),False)
131+
msg.arm_high_spd_feedback_2.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4))
132132
msg.arm_high_spd_feedback_2.pos = self.ConvertToNegative_32bit(self.ConvertBytesToInt(can_data,4,8))
133133
elif(can_id == CanIDPiper.ARM_INFO_HIGH_SPD_FEEDBACK_3.value):
134134
msg.type_ = ArmMessageMapping.get_mapping(can_id=can_id)
135135
msg.arm_high_spd_feedback_3.can_id = can_id
136136
msg.arm_high_spd_feedback_3.motor_speed = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,0,2))
137-
msg.arm_high_spd_feedback_3.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4),False)
137+
msg.arm_high_spd_feedback_3.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4))
138138
msg.arm_high_spd_feedback_3.pos = self.ConvertToNegative_32bit(self.ConvertBytesToInt(can_data,4,8))
139139
elif(can_id == CanIDPiper.ARM_INFO_HIGH_SPD_FEEDBACK_4.value):
140140
msg.type_ = ArmMessageMapping.get_mapping(can_id=can_id)
141141
msg.arm_high_spd_feedback_4.can_id = can_id
142142
msg.arm_high_spd_feedback_4.motor_speed = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,0,2))
143-
msg.arm_high_spd_feedback_4.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4),False)
143+
msg.arm_high_spd_feedback_4.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4))
144144
msg.arm_high_spd_feedback_4.pos = self.ConvertToNegative_32bit(self.ConvertBytesToInt(can_data,4,8))
145145
elif(can_id == CanIDPiper.ARM_INFO_HIGH_SPD_FEEDBACK_5.value):
146146
msg.type_ = ArmMessageMapping.get_mapping(can_id=can_id)
147147
msg.arm_high_spd_feedback_5.can_id = can_id
148148
msg.arm_high_spd_feedback_5.motor_speed = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,0,2))
149-
msg.arm_high_spd_feedback_5.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4),False)
149+
msg.arm_high_spd_feedback_5.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4))
150150
msg.arm_high_spd_feedback_5.pos = self.ConvertToNegative_32bit(self.ConvertBytesToInt(can_data,4,8))
151151
elif(can_id == CanIDPiper.ARM_INFO_HIGH_SPD_FEEDBACK_6.value):
152152
msg.type_ = ArmMessageMapping.get_mapping(can_id=can_id)
153153
msg.arm_high_spd_feedback_6.can_id = can_id
154154
msg.arm_high_spd_feedback_6.motor_speed = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,0,2))
155-
msg.arm_high_spd_feedback_6.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4),False)
155+
msg.arm_high_spd_feedback_6.current = self.ConvertToNegative_16bit(self.ConvertBytesToInt(can_data,2,4))
156156
msg.arm_high_spd_feedback_6.pos = self.ConvertToNegative_32bit(self.ConvertBytesToInt(can_data,4,8))
157157
# 驱动器信息低速反馈,Low-Speed Driver Information Feedback
158158
elif(can_id == CanIDPiper.ARM_INFO_LOW_SPD_FEEDBACK_1.value):

0 commit comments

Comments
 (0)