carm 0.0.20250911__tar.gz → 0.1.20251010__tar.gz

This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: carm
3
- Version: 0.0.20250911
3
+ Version: 0.1.20251010
4
4
  Summary: Python interface for cvte arm.
5
5
  Author-email: Yong Zhao <zhaoyong11933@cvte.com>
6
6
  Classifier: Programming Language :: Python :: 3
@@ -425,6 +425,20 @@ class Carm:
425
425
  def move_pvt(self, target_traj, gripper_pos = [], stamps = [], is_sync=True):
426
426
  pass # TODO
427
427
 
428
+ def set_redundancy_tau(self, redundancy_tau, end_effector=None):
429
+ """
430
+ 设置冗余关节的力矩
431
+ Args:
432
+ redundancy_tau (list): The redundancy joint torque.
433
+ end_effector (int, optional): The end effector index.
434
+ Returns:
435
+ dict: The response from the arm.
436
+ """
437
+ return self.request({"command":"setRedundancyTau",
438
+ "arm_index":0,
439
+ "is_master":True,
440
+ "redundancy_tau":redundancy_tau})
441
+
428
442
  def invK(self, cart_pose, ref_joints, user=0, tool=0):
429
443
  """
430
444
  逆解
@@ -466,6 +480,17 @@ class Carm:
466
480
  def __cbk_status(self, message):
467
481
  self.state = message
468
482
 
483
+ if not "arm" in message:
484
+ return
485
+
486
+ arm_json = message["arm"][0]
487
+ if "last_task_key" not in arm_json:
488
+ return
489
+
490
+ task = arm_json["last_task_key"]
491
+ self.task_pool[task]["event"].set()
492
+
493
+
469
494
  def __cbk_taskfinish(self, message):
470
495
  task = message["task_key"]
471
496
  self.task_pool[task]["event"].set()
@@ -13,10 +13,7 @@ class ArmDriver:
13
13
  self.args = args
14
14
 
15
15
  self.arm = carm.Carm(args.addr)
16
- if args.mit:
17
- self.arm.set_control_mode(3)
18
- else:
19
- self.arm.set_control_mode(1)
16
+ self.arm.set_control_mode(args.mode)
20
17
 
21
18
  self.arm.set_speed_level(args.speed)
22
19
 
@@ -28,8 +25,14 @@ class ArmDriver:
28
25
  self.sub_end = messenger.subscribe(args.end_cmd_topic, 0, lambda msg:self.end_callback(msg))
29
26
 
30
27
  def end_callback(self, msg):
31
- position = np.frombuffer(msg["position"],dtype=np.float64).tolist()
32
- self.arm.track_pose(position)
28
+ position = msg["position"]
29
+ if type(position) != tuple:
30
+ position = np.frombuffer(msg["position"],dtype=np.float64).tolist()
31
+
32
+ if position > 7:
33
+ self.arm.track_pose(position[:7], position[7])
34
+ else:
35
+ self.arm.track_pose(position)
33
36
 
34
37
  if self.args.enable_ik:
35
38
  ret = self.arm.invK(position, ref_joints=self.arm.joint_pos)
@@ -41,9 +44,15 @@ class ArmDriver:
41
44
  self.pub_joint_ik.publish({"header": msg["header"], "position": pos})
42
45
 
43
46
 
44
- def joint_callback(self, msg):
45
- position = np.frombuffer(msg["position"],dtype=np.float64).tolist()
46
- self.arm.track_joint(position)
47
+ def joint_callback(self, msg):
48
+ position = msg["position"]
49
+ if type(position) != tuple:
50
+ position = np.frombuffer(msg["position"],dtype=np.float64).tolist()
51
+
52
+ if position > 6:
53
+ self.arm.track_joint(position[:6], position[6])
54
+ else:
55
+ self.arm.track_joint(position)
47
56
 
48
57
  def loop(self):
49
58
  while True:
@@ -52,8 +61,12 @@ class ArmDriver:
52
61
  nanosec = int((stamp - sec) * 1e9)
53
62
  header = {"stamp": {"sec": sec, "nanosec": nanosec},"frame_id": "base_link"}
54
63
 
55
- end_msg = {"header": header, "position": self.arm.cart_pose + [self.arm.gripper_state["gripper_pos"],]}
56
- joints_msg = {"header": header, "position": self.arm.joint_pos + [self.arm.gripper_state["gripper_pos"],]}
64
+ end_msg = {"header": header,
65
+ "position": self.arm.cart_pose + [self.arm.gripper_state["gripper_pos"],]}
66
+ joints_msg = {"header": header,
67
+ "position": self.arm.joint_pos + [self.arm.gripper_state["gripper_pos"],],
68
+ "velocity": self.arm.joint_vel + [self.arm.gripper_state["gripper_vel"],],
69
+ "effort": self.arm.joint_tau + [self.arm.gripper_state["gripper_tau"],]}
57
70
 
58
71
  self.pub_joint.publish(joints_msg)
59
72
  self.pub_end.publish(end_msg)
@@ -92,13 +105,13 @@ def main():
92
105
  parser.add_argument("--cmd", type=str, default="", help="Send command instead of start driver, support enable,disable,remote")
93
106
  parser.add_argument("--device", type=str, default="carm", help="device name, used as topic prefix")
94
107
  parser.add_argument("--dds", type=str, default="svar_messenger_ros2", help="the dds plugin, default is ros2, options: svar_zbus, svar_lcm")
95
- parser.add_argument("--mit", action="store_true", help="Enable mit mode")
108
+ parser.add_argument("--mode", type=int, default=1, help="The arm control mode: POSITION:1, MIT:2, MASTER:3")
96
109
  parser.add_argument("--joint_topic", type=str, default="", help="the joints status topic")
97
110
  parser.add_argument("--end_topic", type=str, default="", help="the joints status topic")
98
111
  parser.add_argument("--joint_cmd_topic", type=str, default="", help="the joints cmd topic")
99
112
  parser.add_argument("--joint_cmd_ik_topic", type=str, default="", help="the joints cmd ik topic, this means both end_cmd_topic will be transformed with ik")
100
113
  parser.add_argument("--end_cmd_topic", type=str, default="", help="the end cmd topic")
101
- parser.add_argument("--speed", type=float, default=5.0, help="the speed level")
114
+ parser.add_argument("--speed", type=float, default=50.0, help="the speed level")
102
115
 
103
116
  args = parser.parse_args()
104
117
 
@@ -46,9 +46,9 @@ class ArmDriver(Node):
46
46
  while True:
47
47
  joint_msg = JointState() # list of string
48
48
  joint_msg.header.stamp = self.get_clock().now().to_msg()
49
- joint_msg.position = self.arm.joint_pos
50
- joint_msg.velocity = self.arm.joint_vel
51
- joint_msg.effort = self.arm.joint_tau
49
+ joint_msg.position = np.array(self.arm.joint_pos).tolist()
50
+ joint_msg.velocity = np.array(self.arm.joint_vel).tolist()
51
+ joint_msg.effort = np.array(self.arm.joint_tau).tolist()
52
52
  joint_msg.position.append(self.arm.gripper_state["gripper_pos"])
53
53
  self.pub_joint.publish(joint_msg)
54
54
 
@@ -1,6 +1,6 @@
1
1
  Metadata-Version: 2.1
2
2
  Name: carm
3
- Version: 0.0.20250911
3
+ Version: 0.1.20251010
4
4
  Summary: Python interface for cvte arm.
5
5
  Author-email: Yong Zhao <zhaoyong11933@cvte.com>
6
6
  Classifier: Programming Language :: Python :: 3
@@ -4,7 +4,7 @@ build-backend = "setuptools.build_meta"
4
4
 
5
5
  [project]
6
6
  name = "carm"
7
- version = "0.0.20250911"
7
+ version = "0.1.20251010"
8
8
  authors = [
9
9
  {name = "Yong Zhao", email = "zhaoyong11933@cvte.com"},
10
10
  ]
File without changes
File without changes