-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathlinkarm.py
More file actions
2131 lines (1752 loc) · 78.3 KB
/
linkarm.py
File metadata and controls
2131 lines (1752 loc) · 78.3 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
from __future__ import annotations
import json
import threading
import time
from collections import deque
from pathlib import Path
from typing import Any, Deque, Dict, List, Optional, Sequence
import math
import argparse
import shlex
import serial
import serial.tools.list_ports
try:
from scservo_sdk import PortHandler, scscl, COMM_SUCCESS
except Exception:
PortHandler = None
scscl = None
COMM_SUCCESS = 0
class RobotController:
"""
Robot controller
Design goals:
1. Use a dedicated I/O thread to own the bus and avoid read/write collisions.
2. For high-rate joint commands, only keep the newest target and allow older ones to be dropped.
3. Low-frequency but important commands such as LED / switch / PWM are queued reliably and must not be dropped.
4. The interpolation/planner thread never touches the bus directly; it only generates targets and passes them to the high-rate motion slot.
5. When a new interpolated target arrives, the previous trajectory is invalidated immediately and control switches to the new one.
机器人控制器
设计目标:
1. 单 I/O 线程独占总线,避免读写冲突
2. 高频关节命令:只保留最新值,可丢弃旧值
3. 灯光/开关/PWM 等低频但重要命令:进入可靠队列,不能丢
4. 插值线程不直接访问总线,只生成目标点并交给高频关节槽
5. 新插值目标到来时,立即打断旧轨迹,转向新目标
"""
def __init__(
self,
config_path: str = "arm_config.json",
communication_mode: str = "direct_servo",
serial_port: Optional[str] = None,
baudrate: Optional[int] = None,
device_keyword: Optional[str] = None,
timeout: float = 0.001,
write_timeout: float = 0.001,
auto_connect: bool = True,
direct_read_period: float = 0.02,
json_read_chunk: int = 256,
planner_period: float = 0.001, # 插值线程步进周期 / planner thread step period
):
self.config_path = str(Path(config_path).expanduser().resolve())
self.communication_mode = communication_mode.strip().lower()
if self.communication_mode not in ["direct_servo", "json"]:
raise ValueError("communication_mode must be 'direct_servo' or 'json'")
self.timeout = timeout
self.write_timeout = write_timeout
self.direct_read_period = direct_read_period
self.json_read_chunk = json_read_chunk
self.planner_period = planner_period
self.config = self._load_config(self.config_path)
self.linkarm_cfg = self.config.get("linkarm", {})
self.joint_cfg = self.config.get("joint", {})
self.device_keyword = device_keyword or self.linkarm_cfg.get("device_info_keyword", "CH343")
self.serial_port_name = (
serial_port
or self.linkarm_cfg.get("default_device_serial_ports")
)
self.baudrate = int(baudrate or self.linkarm_cfg.get("serial_baudrate", 500000))
self.gripper_torque_limit = int(self.linkarm_cfg.get("gripper_torque_limit", 200))
self.node_id = int(self.linkarm_cfg.get("node_id", 40))
self.joint_type = self.linkarm_cfg.get("joint_type", "scs")
self.joint_info = self.joint_cfg.get(self.joint_type, {})
self.joint_range_rad = float(self.joint_info.get("joint_range_rad", 3.8397))
self.joint_range_steps = int(self.joint_info.get("joint_range_steps", 1024))
self.rad_to_step_coefficient = self.joint_range_steps / self.joint_range_rad
self.id_address = int(self.joint_info.get("id_address", 5))
self.torque_limit_address = int(self.joint_info.get("torque_limit_address", 16))
self.torque_lock_address = int(self.joint_info.get("torque_lock_address", 40))
self.joint_ids = list(self.linkarm_cfg.get("joint_id", [31, 32, 33, 34]))
self.servo_middle = list(self.linkarm_cfg.get("servo_middle", [512, 512, 512, 512]))
self.joint_direction = list(self.linkarm_cfg.get("joint_direction", [1, 1, 1, 1]))
self.joint_limit = list(self.linkarm_cfg.get("joint_limit", [
[-1.5708, 1.5708],
[-1.5708, 1.5708],
[-0.8, 2],
[-1.5, 0]
]))
self.joint_count = len(self.joint_ids)
self.serial_connection: Optional[serial.Serial] = None
self.port_handler = None
self.packet_handler = None
# =============================
# IK 参数预计算 / IK parameter pre-computation
# 提前把几何尺寸换算成后续 IK/FK 计算更方便使用的形式。
# Precompute geometric parameters used repeatedly by IK/FK routines.
# =============================
self.l_ab = self.linkarm_cfg.get("link_ab")
self.l_bc = self.linkarm_cfg.get("link_bc")
self.l_ac = self.l_ab + self.l_bc
self.l_cd = math.sqrt(pow(self.linkarm_cfg.get("link_cd_1"), 2)+pow(self.linkarm_cfg.get("link_cd_2"), 2))
self.l_de = self.linkarm_cfg.get("link_de")
self.l_ef = self.linkarm_cfg.get("link_ef")
self.l_bf = math.sqrt(pow(self.linkarm_cfg.get("link_bf_1"), 2)+pow(self.linkarm_cfg.get("link_bf_2"), 2))
self.l_bf_rad = math.atan2(self.linkarm_cfg.get("link_bf_1"), self.linkarm_cfg.get("link_bf_2"))
self.ik_status = False
self.current_xyzg = [self.l_ab + self.linkarm_cfg.get("link_bf_1") + (self.l_ef/2),
0,
self.linkarm_cfg.get("link_bf_2"),
0
]
# =============================
# 总线与线程控制 / Bus and thread control
# 用事件和锁协调 I/O 线程、规划线程与主线程之间的访问。
# Events and locks coordinate the I/O thread, planner thread, and caller thread.
self.stop_event = threading.Event()
self.wakeup_event = threading.Event()
self.io_thread: Optional[threading.Thread] = None
self.bus_lock = threading.RLock()
# =============================
# 分槽命令设计 / Split command-lane design
# 不同优先级的命令进入不同槽位,避免高频命令挤掉关键控制。
# Commands with different priorities go to different lanes so bursty motion traffic does not starve critical controls.
# =============================
# 高频槽:关节/底盘控制,只保留最新 / High-rate slot: joint/chassis control, keep newest only
self.pending_joint_motion: Optional[Dict[str, Any]] = None
# 可靠队列:灯光、开关、PWM 等,不能丢 / Reliable queue: LED, switch, PWM, etc. must not be lost
self.pending_reliable_commands: Deque[Dict[str, Any]] = deque()
# json 模式写入:高频槽 / JSON-mode write slot for high-rate commands
self.pending_json_write: Optional[Dict[str, Any]] = None
self.pending_lock = threading.Lock()
# =============================
# 反馈缓存 / Feedback caches
# 保存最近一次反馈、最近一次关节角,以及 JSON 接收缓冲区。
# Store the latest feedback, latest joint radians, and the JSON RX buffers.
# =============================
self.latest_feedback_lock = threading.Lock()
self.latest_feedback: Dict[str, Any] = {
"timestamp": 0.0,
"mode": self.communication_mode,
"joints": {}
}
self.last_joint_radians_lock = threading.Lock()
self.last_joint_radians: List[float] = [0.0] * self.joint_count
# JSON 接收缓存 / JSON receive buffer
self.json_rx_buffer = bytearray()
self.json_rx_queue: List[Dict[str, Any]] = []
self.json_rx_lock = threading.Lock()
self.last_direct_read_time = 0.0
# =============================
# 插值 / 规划线程 / Interpolation and planner thread
# 负责把笛卡尔目标离散成一系列小步关节目标。
# Responsible for discretizing a Cartesian target into a sequence of small joint targets.
# =============================
self.planner_wakeup_event = threading.Event()
self.planner_thread: Optional[threading.Thread] = None
self.planner_lock = threading.Lock()
self.planner_target: Optional[Dict[str, Any]] = None
self.planner_generation: int = 0
if auto_connect:
try:
self.connect()
except:
self.disconnect()
time.sleep(0.1)
self.connect()
self.torque_limit(self.joint_ids[0], 1000)
self.torque_limit(self.joint_ids[1], 1000)
self.torque_limit(self.joint_ids[2], 1000)
self.torque_limit(self.joint_ids[3], self.gripper_torque_limit)
# =====================================================
# 基础功能 / Basic helpers
# =====================================================
def _load_config(self, path: str) -> Dict[str, Any]:
"""
加载配置文件 / Load configuration file.
从 JSON 文件读取整机参数、关节参数和通信参数。
Read robot, joint, and communication parameters from a JSON file.
"""
with open(path, "r", encoding="utf-8") as f:
return json.load(f)
def guess_serial_device(self, keyword: str = "CH343") -> Optional[str]:
"""
猜测最匹配的串口设备 / Guess the best-matching serial device.
会遍历系统串口,把 device/description/manufacturer/product/hwid 合并后做关键字匹配。
Iterates over system serial ports and performs keyword matching across multiple descriptor fields.
"""
keyword = keyword.lower()
matched = []
for port in serial.tools.list_ports.comports():
text = " ".join([
str(port.device or ""),
str(port.description or ""),
str(port.manufacturer or ""),
str(port.product or ""),
str(port.hwid or ""),
]).lower()
if keyword in text:
matched.append(port.device)
if not matched:
return None
if len(matched) == 1:
return matched[0]
return matched[-1]
def resolve_serial_port(self) -> str:
"""
解析实际串口号 / Resolve the actual serial port name.
优先使用显式指定端口,其次使用配置中的默认端口,最后再尝试关键字猜测。
Prefer the explicit port, then the configured default port, and finally keyword-based guessing.
"""
if self.serial_port_name:
return self.serial_port_name
guessed = self.guess_serial_device(self.device_keyword)
if guessed:
self.serial_port_name = guessed
return guessed
raise RuntimeError(f"No Keyword: {self.device_keyword} device found")
def rad_to_step(self, joint_index: int, rad: float) -> int:
"""将关节弧度换算为舵机步数 / Convert joint radians to servo steps."""
return int(round(self.servo_middle[joint_index] + rad * self.rad_to_step_coefficient))
def clamp_joint_rad(self, joint_index: int, rad: float) -> float:
"""按关节限位裁剪单个关节角 / Clamp one joint angle using configured joint limits."""
if not (0 <= joint_index < self.joint_count):
raise IndexError(f"joint_index out of range: {joint_index}")
limit_cfg = self.joint_limit[joint_index] if joint_index < len(self.joint_limit) else None
if (
isinstance(limit_cfg, (list, tuple))
and len(limit_cfg) >= 2
and limit_cfg[0] is not None
and limit_cfg[1] is not None
):
low = float(limit_cfg[0])
high = float(limit_cfg[1])
if low > high:
low, high = high, low
return max(low, min(high, float(rad)))
return float(rad)
def clamp_joint_radians(self, joint_radians: Sequence[float]) -> List[float]:
"""批量裁剪关节角 / Clamp a sequence of joint angles."""
result: List[float] = []
for i, rad in enumerate(joint_radians):
if i >= self.joint_count:
break
result.append(self.clamp_joint_rad(i, rad))
return result
@property
def is_connected(self) -> bool:
if self.communication_mode == "json":
return self.serial_connection is not None and self.serial_connection.is_open
return self.port_handler is not None and self.packet_handler is not None
# =====================================================
# 连接 / Connection management
# =====================================================
def connect(self):
"""建立通信并启动后台线程 / Establish communication and start background threads."""
if self.communication_mode == "direct_servo":
self._connect_direct_servo()
else:
self._connect_json()
self._start_io_thread()
self._start_planner_thread()
def disconnect(self):
"""断开通信并停止后台线程 / Disconnect communication and stop background threads."""
self._stop_planner_thread()
self._stop_io_thread()
with self.bus_lock:
if self.serial_connection is not None:
try:
if self.serial_connection.is_open:
self.serial_connection.close()
except Exception:
pass
self.serial_connection = None
if self.port_handler is not None:
try:
self.port_handler.closePort()
except Exception:
pass
self.port_handler = None
self.packet_handler = None
def _connect_direct_servo(self):
"""初始化 direct_servo 模式 / Initialize direct_servo mode."""
if PortHandler is None or scscl is None:
raise ImportError("没有找到 scservo_sdk")
port = self.resolve_serial_port()
self.port_handler = PortHandler(port)
self.packet_handler = scscl(self.port_handler)
if not self.port_handler.openPort():
raise RuntimeError(f"打开串口失败: {port}")
if not self.port_handler.setBaudRate(self.baudrate):
raise RuntimeError(f"设置波特率失败: {self.baudrate}")
def _connect_json(self):
"""初始化 JSON 串口模式 / Initialize JSON-over-UART mode."""
port = self.resolve_serial_port()
self.serial_connection = serial.Serial(
port=port,
baudrate=self.baudrate,
timeout=self.timeout,
write_timeout=self.write_timeout,
)
try:
self.serial_connection.reset_input_buffer()
self.serial_connection.reset_output_buffer()
except Exception:
pass
# =====================================================
# I/O 线程 / I/O thread
# =====================================================
def _start_io_thread(self):
"""启动总线 I/O 线程 / Start the bus I/O thread."""
if self.io_thread is not None and self.io_thread.is_alive():
return
self.stop_event.clear()
self.wakeup_event.clear()
self.io_thread = threading.Thread(target=self._io_loop, daemon=True)
self.io_thread.start()
def _stop_io_thread(self):
"""停止总线 I/O 线程 / Stop the bus I/O thread."""
self.stop_event.set()
self.wakeup_event.set()
if self.io_thread is not None and self.io_thread.is_alive():
self.io_thread.join(timeout=0.5)
self.io_thread = None
def _io_loop(self):
"""
I/O 主循环 / I/O main loop
优先级 / Priority:
1. reliable queue(不能丢的控制)
Reliable queue: must-deliver commands.
2. joint motion slot(高频、可丢)
Joint motion slot: high-rate commands where older targets may be dropped.
3. 读取反馈
Read feedback when there is no pending write work.
"""
idle_wait = 0.002
while not self.stop_event.is_set():
did_work = False
reliable_cmd, joint_cmd, json_cmd = self._take_pending_writes()
if reliable_cmd is not None:
try:
if self.communication_mode == "direct_servo":
self._execute_direct_command_now(reliable_cmd)
else:
self._execute_json_write_now(reliable_cmd)
except Exception as e:
print("[io_loop] reliable write failed:", e)
did_work = True
elif joint_cmd is not None:
try:
if self.communication_mode == "direct_servo":
self._execute_direct_command_now(joint_cmd)
else:
self._execute_json_write_now(joint_cmd)
except Exception as e:
print("[io_loop] joint write failed:", e)
did_work = True
elif json_cmd is not None:
try:
self._execute_json_write_now(json_cmd)
except Exception as e:
print("[io_loop] json write failed:", e)
did_work = True
if not did_work:
try:
if self.communication_mode == "direct_servo":
now = time.perf_counter()
if now - self.last_direct_read_time >= self.direct_read_period:
self._read_direct_feedback_once()
self.last_direct_read_time = now
did_work = True
else:
if self._read_json_available_once():
did_work = True
except Exception as e:
print("[io_loop] read failed:", e)
if not did_work:
self.wakeup_event.wait(idle_wait)
self.wakeup_event.clear()
def _take_pending_writes(self):
"""
取出当前待发送命令 / Pop pending commands for one I/O cycle.
顺序为:可靠队列 -> 关节高频槽 -> JSON 高频槽。
Order: reliable queue -> joint motion slot -> JSON write slot.
"""
with self.pending_lock:
reliable_cmd = None
if self.pending_reliable_commands:
reliable_cmd = self.pending_reliable_commands.popleft()
joint_cmd = self.pending_joint_motion
self.pending_joint_motion = None
json_cmd = self.pending_json_write
self.pending_json_write = None
return reliable_cmd, joint_cmd, json_cmd
# =====================================================
# 对外写接口 / Public write APIs
# =====================================================
def move_joints_rad_sync(
self,
joint_radians: Sequence[float],
speed,
acc,
blocking: bool = False,
):
"""
同步下发多关节目标 / Submit a multi-joint target.
这里的 “sync” 指的是同一组关节目标作为一个整体发送,
不一定意味着调用线程阻塞等待执行完成。
Here, "sync" means the joint targets are sent as one synchronized group,
not necessarily that the caller blocks until motion finishes.
"""
joint_radians = self.clamp_joint_radians(list(joint_radians))
joint_count = len(joint_radians)
if isinstance(speed, int):
speed = [speed] * joint_count
else:
speed = list(speed)
if isinstance(acc, int):
acc = [acc] * joint_count
else:
acc = list(acc)
if len(speed) < joint_count:
speed += [0] * (joint_count - len(speed))
if len(acc) < joint_count:
acc += [0] * (joint_count - len(acc))
cmd = {
"type": "move_joints",
"joint_radians": joint_radians,
"speed": speed,
"acc": acc,
}
if blocking:
if self.communication_mode == "direct_servo":
return self._execute_direct_command_now(cmd)
return self._execute_json_write_now({
"cmd": "move_joints",
"joints_rad": list(joint_radians),
"speed": speed,
})
if self.communication_mode == "direct_servo":
with self.pending_lock:
self.pending_joint_motion = cmd
self.wakeup_event.set()
return None
payload = {
"cmd": "move_joints",
"joints_rad": list(joint_radians),
"speed": speed,
}
with self.pending_lock:
self.pending_json_write = payload
self.wakeup_event.set()
return None
def move_joint_rad(
self,
joint_index: int,
rad: float,
speed: int = 0,
acc: int = 0,
blocking: bool = False,
):
"""
移动单个关节 / Move one joint.
内部会先读取最近一次缓存的关节角,再只修改指定关节后整体下发。
Internally it starts from the cached latest joint state, modifies the requested joint,
and then sends the whole joint set.
"""
joints = self.get_last_joint_radians()
if 0 <= joint_index < len(joints):
joints[joint_index] = self.clamp_joint_rad(joint_index, rad)
speed_list = [0] * len(joints)
acc_list = [0] * len(joints)
speed_list[joint_index] = speed
acc_list[joint_index] = acc
return self.move_joints_rad_sync(
joints,
speed=speed_list,
acc=acc_list,
blocking=blocking,
)
else:
return None
def set_bus_address_1byte_value(self, device_id: int, address: int, value: int):
"""向总线设备写入 1 字节寄存器 / Write a 1-byte register on the bus device."""
'''
Reliable cmd
'''
cmd = {
"type":"set_1byte_value",
"id":device_id,
"address": address,
"value": value
}
self._enqueue_reliable_command(cmd)
def set_bus_address_2byte_value(self, device_id: int, address: int, value: int):
"""向总线设备写入 2 字节寄存器 / Write a 2-byte register on the bus device."""
'''
Reliable cmd
'''
cmd = {
"type":"set_2byte_value",
"id":device_id,
"address": address,
"value": value
}
self._enqueue_reliable_command(cmd)
def set_led_async(self, r: int, g: int, b: int):
"""
Reliable cmd
"""
r = max(0, min(8, r))
g = max(0, min(8, g))
b = max(0, min(8, b))
r2 = int(r * 3 / 8) # 0~3
g3 = int(g * 7 / 8) # 0~7
b2 = int(b * 3 / 8) # 0~3
rgb232 = (((g3 << 5) | (r2 << 2) | b2) << 1) & 0xFF
self.set_bus_address_1byte_value(self.node_id, 43, rgb232)
self.set_bus_address_1byte_value(self.node_id, 44, rgb232)
self.set_bus_address_1byte_value(self.node_id, 42, 2)
def set_pwm_async(self, channel: int, pwm: int):
"""异步设置 PWM 输出 / Set PWM output asynchronously."""
if channel == 0:
self.set_bus_address_2byte_value(self.node_id, 34, pwm)
elif channel == 1:
self.set_bus_address_2byte_value(self.node_id, 36, pwm)
def _enqueue_reliable_command(self, cmd: Dict[str, Any]):
"""把命令放入可靠队列 / Push a command into the reliable queue."""
with self.pending_lock:
self.pending_reliable_commands.append(cmd)
self.wakeup_event.set()
def send_json(self, payload: Dict[str, Any], blocking: bool = False):
"""发送原始 JSON 命令 / Send a raw JSON command."""
if self.communication_mode != "json":
raise RuntimeError("Not in the json mode")
if blocking:
return self._execute_json_write_now(payload)
with self.pending_lock:
self.pending_json_write = payload
self.wakeup_event.set()
return None
# =====================================================
# direct_servo 执行 / direct_servo execution
# =====================================================
def _execute_direct_command_now(self, cmd: Dict[str, Any]):
"""立即执行 direct_servo 命令 / Execute a direct_servo command immediately."""
if self.packet_handler is None:
raise RuntimeError("direct_servo not initialized yet")
cmd_type = cmd.get("type")
if not cmd_type:
raise ValueError("direct command missing 'type'")
with self.bus_lock:
if cmd_type == "move_joints":
return self._direct_write_move_joints(cmd)
elif cmd_type == "set_1byte_value":
return self.packet_handler.write1ByteTxRx(cmd["id"], cmd["address"], cmd["value"])
elif cmd_type == "set_2byte_value":
return self.packet_handler.write2ByteTxRx(cmd["id"], cmd["address"], cmd["value"])
elif cmd_type == "set_led":
return self._direct_write_set_led(cmd)
elif cmd_type == "set_pwm":
return self._direct_write_set_pwm(cmd)
elif cmd_type == "set_switch":
return self._direct_write_set_switch(cmd)
else:
raise ValueError(f"unsupported direct command type: {cmd_type}")
def _direct_write_move_joints(self, cmd: Dict[str, Any]):
"""直接下发多关节目标 / Write a multi-joint target directly to the servo bus."""
joint_radians = cmd["joint_radians"]
speed = cmd["speed"]
acc = cmd["acc"]
goal_positions = []
for i, rad in enumerate(joint_radians):
if i >= self.joint_count:
break
goal_pos = self.rad_to_step(i, rad)
servo_id = self.joint_ids[i]
ok = self.packet_handler.SyncWritePos(servo_id, goal_pos, acc[i], speed[i])
if ok is not True:
raise RuntimeError(f"SyncWritePos failed, id={servo_id}")
goal_positions.append(goal_pos)
comm_result = self.packet_handler.groupSyncWrite.txPacket()
if comm_result != COMM_SUCCESS:
err = self.packet_handler.getTxRxResult(comm_result)
self.packet_handler.groupSyncWrite.clearParam()
raise RuntimeError(err)
self.packet_handler.groupSyncWrite.clearParam()
with self.last_joint_radians_lock:
for i in range(min(len(joint_radians), self.joint_count)):
self.last_joint_radians[i] = float(joint_radians[i])
return goal_positions
# =====================================================
# JSON 写入 / JSON writes
# =====================================================
def _execute_json_write_now(self, payload: Dict[str, Any]):
"""立即发送一条 JSON 数据 / Write one JSON payload immediately."""
if self.serial_connection is None or not self.serial_connection.is_open:
raise RuntimeError("json uart not open")
raw = json.dumps(payload, ensure_ascii=False, separators=(",", ":")).encode("utf-8") + b"\n"
with self.bus_lock:
return self.serial_connection.write(raw)
# =====================================================
# direct_servo 读取 / direct_servo reads
# =====================================================
def _read_direct_feedback_once(self):
"""轮询一次 direct_servo 反馈 / Poll direct_servo feedback once."""
if self.packet_handler is None:
return
joints = {}
with self.bus_lock:
for index in range(len(self.joint_ids)):
snapshot = self._ft_read_snapshot_one(index)
joints[index] = snapshot
with self.latest_feedback_lock:
self.latest_feedback = {
"timestamp": time.time(),
"mode": "direct_servo",
"joints": joints,
}
def _ft_read_snapshot_one(self, joint_index: int) -> Dict[str, Any]:
"""读取单个关节快照 / Read one joint snapshot."""
if self.packet_handler is None:
raise RuntimeError("direct_servo not initialized yet")
result: Dict[str, Any] = {"id": self.joint_ids[joint_index]}
scs_present_position, scs_present_speed, scs_comm_result, scs_error = self.packet_handler.ReadPosSpeed(
self.joint_ids[joint_index]
)
if scs_comm_result == COMM_SUCCESS:
result["position"] = scs_present_position
result["speed"] = scs_present_speed
result["error"] = scs_error
else:
result["comm"] = "failed"
return result
def get_latest_feedback(self) -> Dict[str, Any]:
"""获取最近一次反馈副本 / Get a copy of the latest feedback."""
with self.latest_feedback_lock:
return dict(self.latest_feedback)
def get_last_joint_radians(self) -> List[float]:
"""获取缓存的最近一次关节弧度 / Get cached latest joint radians."""
with self.last_joint_radians_lock:
return list(self.last_joint_radians)
# =====================================================
# JSON 读取 / JSON reads
# =====================================================
def _read_json_available_once(self) -> bool:
"""尽可能读取一批可用 JSON 数据 / Read one available batch of JSON UART data."""
if self.serial_connection is None or not self.serial_connection.is_open:
return False
did_read = False
with self.bus_lock:
waiting = self.serial_connection.in_waiting
if waiting <= 0:
# 没有串口数据可读 / no UART data available
return False
data = self.serial_connection.read(min(waiting, self.json_read_chunk))
if not data:
return False
self.json_rx_buffer.extend(data)
did_read = True
while b"\n" in self.json_rx_buffer:
line, _, remain = self.json_rx_buffer.partition(b"\n")
self.json_rx_buffer = bytearray(remain)
text = line.decode("utf-8", errors="ignore").strip()
if not text:
continue
try:
obj = json.loads(text)
except Exception:
obj = {"raw": text}
with self.json_rx_lock:
self.json_rx_queue.append(obj)
if len(self.json_rx_queue) > 200:
# 只保留最近 200 条,避免缓存无限增长。
# Keep only the newest 200 messages to avoid unbounded growth.
self.json_rx_queue = self.json_rx_queue[-200:]
with self.latest_feedback_lock:
self.latest_feedback = {
"timestamp": time.time(),
"mode": "json",
"data": obj,
}
return did_read
def read_json_message(self) -> Optional[Dict[str, Any]]:
"""从接收队列取出一条 JSON 消息 / Pop one decoded JSON message from the RX queue."""
with self.json_rx_lock:
if not self.json_rx_queue:
return None
return self.json_rx_queue.pop(0)
# =====================================================
# 插值 / 规划线程 / Interpolation planner thread
# =====================================================
def _start_planner_thread(self):
"""启动规划线程 / Start the planner thread."""
if self.planner_thread is not None and self.planner_thread.is_alive():
return
self.planner_wakeup_event.clear()
self.planner_thread = threading.Thread(target=self._planner_loop, daemon=True)
self.planner_thread.start()
def _stop_planner_thread(self):
"""停止规划线程 / Stop the planner thread."""
self.planner_wakeup_event.set()
if self.planner_thread is not None and self.planner_thread.is_alive():
self.planner_thread.join(timeout=0.5)
self.planner_thread = None
def ik_ctrl(self, goal_position: Sequence[float], speed: float = 880):
"""
用户接口 / User API:
ik_ctrl([x, y, z, g], speed)
非阻塞 / Non-blocking:
- 只写入新的规划目标
Only stores a new planner target.
- 规划线程被唤醒
Wakes up the planner thread.
- 旧轨迹自动失效,转向新目标
The previous trajectory becomes invalid automatically and execution switches to the new target.
"""
if len(goal_position) != 4:
raise ValueError("goal_position must be [x, y, z, g]")
with self.planner_lock:
self.planner_generation += 1
self.planner_target = {
"goal_position": list(goal_position),
"speed": float(speed),
"generation": self.planner_generation,
}
self.planner_wakeup_event.set()
def _planner_loop(self):
"""
规划线程主循环 / Planner thread main loop
规划线程不直接访问串口。
The planner thread never talks to the serial bus directly.
它只负责 / Responsibilities:
1. 取当前目标 / Fetch the current target.
2. 计算当前末端到目标末端的插值点 / Interpolate Cartesian waypoints from current pose to goal pose.
3. 每一步调用 ik_generate() -> joints / Convert each waypoint into joint targets through IK.
4. 再调用 move_joints_rad_sync(..., blocking=False) / Submit non-blocking joint targets to the motion slot.
新目标到来时,通过 generation 机制让旧轨迹立刻失效。
When a new target arrives, the generation counter invalidates the old trajectory immediately.
"""
while not self.stop_event.is_set():
self.planner_wakeup_event.wait()
self.planner_wakeup_event.clear()
while not self.stop_event.is_set():
with self.planner_lock:
task = self.planner_target
if task is None:
break
my_generation = int(task["generation"])
goal_position = list(task["goal_position"])
speed = float(task["speed"])
current_pose = self.current_xyzg
delta = [goal_position[i] - current_pose[i] for i in range(3)]
distance = max(abs(v) for v in delta)
if distance < 1e-6:
with self.planner_lock:
if self.planner_target and self.planner_target["generation"] == my_generation:
self.planner_target = None
break
step_distance = max(speed * self.planner_period, 1e-4)
steps = max(int(distance / step_distance), 1)
interrupted = False
for step_idx in range(1, steps + 1):
if self.stop_event.is_set():
return
with self.planner_lock:
latest_generation = self.planner_target["generation"] if self.planner_target else -1
if latest_generation != my_generation:
# 发现更新世代号,说明有新目标覆盖当前轨迹。
# A newer generation means the current trajectory has been superseded.
interrupted = True
break
t = step_idx / steps # 当前插值进度 / current interpolation progress
interp_pose = [
current_pose[i] + delta[i] * t
for i in range(3)
]
joints = self.ik_generate(
interp_pose[0],
interp_pose[1],
interp_pose[2]
)
if joints == False:
# IK 失败通常意味着当前插值点不可达。
# IK failure usually means the current interpolated waypoint is unreachable.
interrupted = True
break
self.move_joints_rad_sync(
joints,
speed=[0] * len(joints),
acc=[0] * len(joints),
blocking=False,
)
time.sleep(self.planner_period)
if interrupted:
continue
with self.planner_lock:
if self.planner_target and self.planner_target["generation"] == my_generation:
self.planner_target = None
break
def ik_ctrl_immediate(self, goal_position: Sequence[float], speed: Sequence[int] = [0,0,0,0]):
"""立即执行 IK,不做插值 / Execute IK immediately without interpolation."""
self.cancel_ik_ctrl()
joints = self.ik_generate(
goal_position[0],
goal_position[1],
goal_position[2]
)
if joints == False:
return False
self.move_joints_rad_sync(
joints,
speed,
acc=[0] * len(joints),
blocking=True,
)
for i in range(len(self.current_xyzg) - 1):
self.current_xyzg[i] = goal_position[i]
return True
def fpv_ctrl_immediate(self, goal_position: Sequence[float], speed: Sequence[int] = [0,0,0,0]):
"""以 base/reach/z 形式立即控制 / Immediate control using base/reach/z coordinates."""
'''
goal_position = [base(rad), reach, z]
'''
self.cancel_ik_ctrl()
input_xyzg_buffer = [math.cos(goal_position[0]) * goal_position[1],
math.sin(goal_position[0]) * goal_position[1],
goal_position[2]]
joints = self.ik_generate(input_xyzg_buffer[0],
input_xyzg_buffer[1],