kuavo-humanoid-sdk 0.1.0__py3-none-any.whl
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.
Potentially problematic release.
This version of kuavo-humanoid-sdk might be problematic. Click here for more details.
- kuavo_humanoid_sdk/__init__.py +3 -0
- kuavo_humanoid_sdk/common/logger.py +42 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +122 -0
- kuavo_humanoid_sdk/interfaces/end_effector.py +43 -0
- kuavo_humanoid_sdk/interfaces/robot.py +22 -0
- kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
- kuavo_humanoid_sdk/kuavo/__init__.py +7 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +388 -0
- kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +85 -0
- kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +758 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +171 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +325 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +196 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +183 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +225 -0
- kuavo_humanoid_sdk/kuavo/robot.py +309 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +140 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +29 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +112 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +258 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/METADATA +217 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/RECORD +27 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/WHEEL +5 -0
- kuavo_humanoid_sdk-0.1.0.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,758 @@
|
|
|
1
|
+
|
|
2
|
+
import rospy
|
|
3
|
+
import numpy as np
|
|
4
|
+
from typing import Tuple
|
|
5
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
6
|
+
from kuavo_humanoid_sdk.interfaces.data_types import KuavoArmCtrlMode, KuavoIKParams, KuavoPose
|
|
7
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.sat_utils import RotatingRectangle
|
|
8
|
+
|
|
9
|
+
from geometry_msgs.msg import Twist
|
|
10
|
+
from sensor_msgs.msg import JointState, Joy
|
|
11
|
+
from kuavo_msgs.msg import gestureTask,robotHandPosition, robotHeadMotionData, armTargetPoses, switchGaitByName
|
|
12
|
+
from kuavo_msgs.msg import footPose, footPoseTargetTrajectories
|
|
13
|
+
from kuavo_msgs.srv import (gestureExecute, gestureExecuteRequest,gestureList, gestureListRequest,
|
|
14
|
+
controlLejuClaw, controlLejuClawRequest, changeArmCtrlMode, changeArmCtrlModeRequest)
|
|
15
|
+
from motion_capture_ik.msg import twoArmHandPoseCmd, ikSolveParam
|
|
16
|
+
from motion_capture_ik.srv import twoArmHandPoseCmdSrv, fkSrv
|
|
17
|
+
|
|
18
|
+
class ControlEndEffector:
|
|
19
|
+
def __init__(self, eef_type: str = "qiangnao"):
|
|
20
|
+
self._pubs = []
|
|
21
|
+
self._eef_type = eef_type
|
|
22
|
+
if eef_type == "qiangnao":
|
|
23
|
+
self._pub_ctrl_robot_hand = rospy.Publisher('/control_robot_hand_position', robotHandPosition, queue_size=10)
|
|
24
|
+
self._pubs.append(self._pub_ctrl_robot_hand)
|
|
25
|
+
|
|
26
|
+
def connect(self, timeout:float=1.0)-> bool:
|
|
27
|
+
start_time = rospy.Time.now()
|
|
28
|
+
|
|
29
|
+
success = True
|
|
30
|
+
for pub in self._pubs:
|
|
31
|
+
while pub.get_num_connections() == 0:
|
|
32
|
+
if (rospy.Time.now() - start_time).to_sec() > timeout:
|
|
33
|
+
SDKLogger.error(f"Timeout waiting for {pub.name} connection")
|
|
34
|
+
success = False
|
|
35
|
+
break
|
|
36
|
+
rospy.sleep(0.1)
|
|
37
|
+
|
|
38
|
+
return success
|
|
39
|
+
|
|
40
|
+
""" Control Kuavo Robot Dexhand """
|
|
41
|
+
def pub_control_robot_dexhand(self, left_position:list, right_position:list)->bool:
|
|
42
|
+
if self._eef_type != 'qiangnao':
|
|
43
|
+
SDKLogger.warning(f"{self._eef_type} not support control dexhand")
|
|
44
|
+
return False
|
|
45
|
+
try :
|
|
46
|
+
hand_pose_msg = robotHandPosition()
|
|
47
|
+
hand_pose_msg.left_hand_position = bytes(left_position)
|
|
48
|
+
hand_pose_msg.right_hand_position = bytes(right_position)
|
|
49
|
+
self._pub_ctrl_robot_hand.publish(hand_pose_msg)
|
|
50
|
+
SDKLogger.debug(f"publish robot dexhand: {left_position}, {right_position}")
|
|
51
|
+
return True
|
|
52
|
+
except Exception as e:
|
|
53
|
+
SDKLogger.error(f"publish robot dexhand: {e}")
|
|
54
|
+
return False
|
|
55
|
+
|
|
56
|
+
def srv_execute_gesture(self, gestures:list)->bool:
|
|
57
|
+
if self._eef_type != 'qiangnao':
|
|
58
|
+
SDKLogger.warning(f"{self._eef_type} not support control dexhand")
|
|
59
|
+
return False
|
|
60
|
+
try:
|
|
61
|
+
service_name = 'gesture/execute'
|
|
62
|
+
rospy.wait_for_service(service=service_name, timeout=2.0)
|
|
63
|
+
# create service proxy
|
|
64
|
+
gesture_service = rospy.ServiceProxy(service_name, gestureExecute)
|
|
65
|
+
|
|
66
|
+
# request
|
|
67
|
+
request = gestureExecuteRequest()
|
|
68
|
+
for gs in gestures:
|
|
69
|
+
gesture = gestureTask(gesture_name=gs["gesture_name"], hand_side=gs["hand_side"])
|
|
70
|
+
request.gestures.append(gesture)
|
|
71
|
+
|
|
72
|
+
# call service
|
|
73
|
+
response = gesture_service(request)
|
|
74
|
+
if not response.success:
|
|
75
|
+
SDKLogger.error(f"Failed to execute gesture '{gestures}': {response.message}")
|
|
76
|
+
return response.success
|
|
77
|
+
except rospy.ServiceException as e:
|
|
78
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
79
|
+
except rospy.ROSException as e:
|
|
80
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
81
|
+
except Exception as e:
|
|
82
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
83
|
+
return False
|
|
84
|
+
|
|
85
|
+
def srv_get_gesture_names(self)->list:
|
|
86
|
+
if self._eef_type != 'qiangnao':
|
|
87
|
+
SDKLogger.warning(f"{self._eef_type} not support control dexhand")
|
|
88
|
+
return []
|
|
89
|
+
try:
|
|
90
|
+
service_name = 'gesture/list'
|
|
91
|
+
rospy.wait_for_service(service=service_name, timeout=2.0)
|
|
92
|
+
gesture_service = rospy.ServiceProxy(service_name, gestureList)
|
|
93
|
+
request = gestureListRequest()
|
|
94
|
+
response = gesture_service(request)
|
|
95
|
+
gestures = []
|
|
96
|
+
for gesture_info in response.gesture_infos:
|
|
97
|
+
gestures.append(gesture_info.gesture_name)
|
|
98
|
+
for alias in gesture_info.alias:
|
|
99
|
+
gestures.append(alias)
|
|
100
|
+
return list(set(gestures))
|
|
101
|
+
except rospy.ServiceException as e:
|
|
102
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
103
|
+
except Exception as e:
|
|
104
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
105
|
+
return []
|
|
106
|
+
|
|
107
|
+
def srv_control_leju_claw(self, postions:list, velocities:list, torques:list) ->bool:
|
|
108
|
+
if self._eef_type != 'lejuclaw':
|
|
109
|
+
SDKLogger.warning(f"{self._eef_type} not support control lejuclaw.")
|
|
110
|
+
return False
|
|
111
|
+
try:
|
|
112
|
+
# ros service
|
|
113
|
+
service_name = 'control_robot_leju_claw'
|
|
114
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
115
|
+
control_lejucalw_srv = rospy.ServiceProxy(service_name, controlLejuClaw)
|
|
116
|
+
|
|
117
|
+
# request
|
|
118
|
+
request = controlLejuClawRequest()
|
|
119
|
+
request.data.position = postions
|
|
120
|
+
request.data.velocity = velocities
|
|
121
|
+
request.data.effort = torques
|
|
122
|
+
|
|
123
|
+
response = control_lejucalw_srv(request)
|
|
124
|
+
if not response.success:
|
|
125
|
+
SDKLogger.error(f"Failed to control leju claw: {response.message}")
|
|
126
|
+
return response.success
|
|
127
|
+
except rospy.ServiceException as e:
|
|
128
|
+
SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
|
|
129
|
+
except rospy.ROSException as e:
|
|
130
|
+
SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
|
|
131
|
+
except Exception as e:
|
|
132
|
+
SDKLogger.error(f"Service `control_robot_leju_claw` call failed: {e}")
|
|
133
|
+
return False
|
|
134
|
+
|
|
135
|
+
""" Control Robot Arm"""
|
|
136
|
+
class ControlRobotArm:
|
|
137
|
+
def __init__(self):
|
|
138
|
+
self._pub_ctrl_arm_traj = rospy.Publisher('/kuavo_arm_traj', JointState, queue_size=10)
|
|
139
|
+
self._pub_ctrl_arm_target_poses = rospy.Publisher('/kuavo_arm_target_poses', armTargetPoses, queue_size=10)
|
|
140
|
+
|
|
141
|
+
def connect(self, timeout:float=1.0)-> bool:
|
|
142
|
+
start_time = rospy.Time.now()
|
|
143
|
+
publishers = [
|
|
144
|
+
(self._pub_ctrl_arm_traj, "arm trajectory publisher"),
|
|
145
|
+
(self._pub_ctrl_arm_target_poses, "arm target poses publisher")
|
|
146
|
+
]
|
|
147
|
+
|
|
148
|
+
success = True
|
|
149
|
+
for pub, name in publishers:
|
|
150
|
+
while pub.get_num_connections() == 0:
|
|
151
|
+
if (rospy.Time.now() - start_time).to_sec() > timeout:
|
|
152
|
+
SDKLogger.error(f"Timeout waiting for {name} connection, '{pub.name}'")
|
|
153
|
+
success = False
|
|
154
|
+
break
|
|
155
|
+
rospy.sleep(0.1)
|
|
156
|
+
return success
|
|
157
|
+
|
|
158
|
+
def pub_control_robot_arm_traj(self, joint_q: list)->bool:
|
|
159
|
+
try:
|
|
160
|
+
msg = JointState()
|
|
161
|
+
msg.name = ["arm_joint_" + str(i) for i in range(0, 14)]
|
|
162
|
+
msg.header.stamp = rospy.Time.now()
|
|
163
|
+
msg.position = 180.0 / np.pi * np.array(joint_q) # convert to degree
|
|
164
|
+
self._pub_ctrl_arm_traj.publish(msg)
|
|
165
|
+
return True
|
|
166
|
+
except Exception as e:
|
|
167
|
+
SDKLogger.error(f"publish robot arm traj: {e}")
|
|
168
|
+
return False
|
|
169
|
+
|
|
170
|
+
def pub_arm_target_poses(self, times:list, joint_q:list):
|
|
171
|
+
try:
|
|
172
|
+
msg = armTargetPoses()
|
|
173
|
+
msg.times = times
|
|
174
|
+
for i in range(len(joint_q)):
|
|
175
|
+
degs = [q for q in joint_q[i]]
|
|
176
|
+
msg.values.extend(degs)
|
|
177
|
+
self._pub_ctrl_arm_target_poses.publish(msg)
|
|
178
|
+
return True
|
|
179
|
+
except Exception as e:
|
|
180
|
+
SDKLogger.error(f"publish arm target poses: {e}")
|
|
181
|
+
return False
|
|
182
|
+
|
|
183
|
+
def srv_change_arm_ctrl_mode(self, mode: KuavoArmCtrlMode)->bool:
|
|
184
|
+
try:
|
|
185
|
+
rospy.wait_for_service('/arm_traj_change_mode', timeout=2.0)
|
|
186
|
+
change_arm_ctrl_mode_srv = rospy.ServiceProxy('/arm_traj_change_mode', changeArmCtrlMode)
|
|
187
|
+
req = changeArmCtrlModeRequest()
|
|
188
|
+
req.control_mode = mode.value
|
|
189
|
+
resp = change_arm_ctrl_mode_srv(req)
|
|
190
|
+
return resp.result
|
|
191
|
+
except rospy.ServiceException as e:
|
|
192
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
193
|
+
except Exception as e:
|
|
194
|
+
SDKLogger.error(f"[Error] change arm ctrl mode: {e}")
|
|
195
|
+
return False
|
|
196
|
+
|
|
197
|
+
def srv_get_arm_ctrl_mode(self)-> KuavoArmCtrlMode:
|
|
198
|
+
try:
|
|
199
|
+
rospy.wait_for_service('/humanoid_get_arm_ctrl_mode')
|
|
200
|
+
get_arm_ctrl_mode_srv = rospy.ServiceProxy('/humanoid_get_arm_ctrl_mode', changeArmCtrlMode)
|
|
201
|
+
req = changeArmCtrlModeRequest()
|
|
202
|
+
resp = get_arm_ctrl_mode_srv(req)
|
|
203
|
+
return KuavoArmCtrlMode(resp.control_mode)
|
|
204
|
+
except rospy.ServiceException as e:
|
|
205
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
206
|
+
except Exception as e:
|
|
207
|
+
SDKLogger.error(f"[Error] get arm ctrl mode: {e}")
|
|
208
|
+
return None
|
|
209
|
+
|
|
210
|
+
""" Control Robot Head """
|
|
211
|
+
class ControlRobotHead:
|
|
212
|
+
def __init__(self):
|
|
213
|
+
self._pub_ctrl_robot_head = rospy.Publisher('/robot_head_motion_data', robotHeadMotionData, queue_size=10)
|
|
214
|
+
|
|
215
|
+
def connect(self, timeout:float=1.0)->bool:
|
|
216
|
+
start_time = rospy.Time.now()
|
|
217
|
+
publishers = [
|
|
218
|
+
# (self._pub_ctrl_robot_head, "robot head publisher") # not need check!
|
|
219
|
+
]
|
|
220
|
+
for pub, name in publishers:
|
|
221
|
+
while pub.get_num_connections() == 0:
|
|
222
|
+
if (rospy.Time.now() - start_time).to_sec() > timeout:
|
|
223
|
+
SDKLogger.error(f"Timeout waiting for {name} connection, '{pub.name}'")
|
|
224
|
+
return False
|
|
225
|
+
rospy.sleep(0.1)
|
|
226
|
+
return True
|
|
227
|
+
def pub_control_robot_head(self, yaw:float, pitch:float)->bool:
|
|
228
|
+
try :
|
|
229
|
+
msg = robotHeadMotionData()
|
|
230
|
+
msg.joint_data = [yaw, pitch]
|
|
231
|
+
self._pub_ctrl_robot_head.publish(msg)
|
|
232
|
+
return True
|
|
233
|
+
except Exception as e:
|
|
234
|
+
SDKLogger.error(f"[Error] publish robot head: {e}")
|
|
235
|
+
return False
|
|
236
|
+
|
|
237
|
+
""" Control Robot Motion """
|
|
238
|
+
|
|
239
|
+
# JoyButton constants
|
|
240
|
+
BUTTON_A = 0
|
|
241
|
+
BUTTON_B = 1
|
|
242
|
+
BUTTON_X = 2
|
|
243
|
+
BUTTON_Y = 3
|
|
244
|
+
BUTTON_LB = 4
|
|
245
|
+
BUTTON_RB = 5
|
|
246
|
+
BUTTON_BACK = 6
|
|
247
|
+
BUTTON_START = 7
|
|
248
|
+
|
|
249
|
+
# JoyAxis constants
|
|
250
|
+
AXIS_LEFT_STICK_Y = 0
|
|
251
|
+
AXIS_LEFT_STICK_X = 1
|
|
252
|
+
AXIS_LEFT_LT = 2 # 1 -> (-1)
|
|
253
|
+
AXIS_RIGHT_STICK_YAW = 3
|
|
254
|
+
AXIS_RIGHT_STICK_Z = 4
|
|
255
|
+
AXIS_RIGHT_RT = 5 # 1 -> (-1)
|
|
256
|
+
AXIS_LEFT_RIGHT_TRIGGER = 6
|
|
257
|
+
AXIS_FORWARD_BACK_TRIGGER = 7
|
|
258
|
+
|
|
259
|
+
class ControlRobotMotion:
|
|
260
|
+
def __init__(self):
|
|
261
|
+
self._pub_cmd_vel = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
|
|
262
|
+
self._pub_cmd_pose = rospy.Publisher('/cmd_pose', Twist, queue_size=10)
|
|
263
|
+
self._pub_joy = rospy.Publisher('/joy', Joy, queue_size=10)
|
|
264
|
+
self._pub_switch_gait = rospy.Publisher('/humanoid_switch_gait_by_name', switchGaitByName, queue_size=10)
|
|
265
|
+
self._pub_step_ctrl = rospy.Publisher('/humanoid_mpc_foot_pose_target_trajectories', footPoseTargetTrajectories, queue_size=10)
|
|
266
|
+
|
|
267
|
+
def connect(self, timeout:float=1.0)-> bool:
|
|
268
|
+
start_time = rospy.Time.now()
|
|
269
|
+
publishers = [
|
|
270
|
+
# (self._pub_joy, "joy publisher"),
|
|
271
|
+
(self._pub_cmd_vel, "cmd_vel publisher"),
|
|
272
|
+
(self._pub_cmd_pose, "cmd_pose publisher"),
|
|
273
|
+
(self._pub_step_ctrl, "step_ctrl publisher"),
|
|
274
|
+
(self._pub_switch_gait, "switch_gait publisher")
|
|
275
|
+
]
|
|
276
|
+
|
|
277
|
+
success = True
|
|
278
|
+
for pub, name in publishers:
|
|
279
|
+
while pub.get_num_connections() == 0:
|
|
280
|
+
if (rospy.Time.now() - start_time).to_sec() > timeout:
|
|
281
|
+
SDKLogger.error(f"Timeout waiting for {name} connection, '{pub.name}'")
|
|
282
|
+
success = False
|
|
283
|
+
break
|
|
284
|
+
rospy.sleep(0.1)
|
|
285
|
+
return success
|
|
286
|
+
|
|
287
|
+
def pub_cmd_vel(self, linear_x: float, linear_y: float, angular_z: float)->bool:
|
|
288
|
+
try:
|
|
289
|
+
twist = Twist()
|
|
290
|
+
twist.linear.x = linear_x
|
|
291
|
+
twist.linear.y = linear_y
|
|
292
|
+
twist.angular.z = angular_z
|
|
293
|
+
self._pub_cmd_vel.publish(twist)
|
|
294
|
+
return True
|
|
295
|
+
except Exception as e:
|
|
296
|
+
SDKLogger.error(f"[Error] publish cmd vel: {e}")
|
|
297
|
+
return False
|
|
298
|
+
|
|
299
|
+
def pub_cmd_pose(self, twist:Twist)->bool:
|
|
300
|
+
try:
|
|
301
|
+
self._pub_cmd_pose.publish(twist)
|
|
302
|
+
return True
|
|
303
|
+
except Exception as e:
|
|
304
|
+
SDKLogger.error(f"[Error] publish cmd pose: {e}")
|
|
305
|
+
return False
|
|
306
|
+
|
|
307
|
+
def _create_joy_msg(self)->Joy:
|
|
308
|
+
joy_msg = Joy()
|
|
309
|
+
joy_msg.axes = [0.0] * 8 # Initialize 8 axes
|
|
310
|
+
joy_msg.buttons = [0] * 16 # Initialize 16 buttons
|
|
311
|
+
return joy_msg
|
|
312
|
+
|
|
313
|
+
def _pub_joy_command(self, button_index: int, command_name: str) -> bool:
|
|
314
|
+
try:
|
|
315
|
+
joy_msg = self._create_joy_msg()
|
|
316
|
+
joy_msg.buttons[button_index] = 1
|
|
317
|
+
self._pub_joy.publish(joy_msg)
|
|
318
|
+
SDKLogger.debug(f"Published {command_name} command")
|
|
319
|
+
return True
|
|
320
|
+
except Exception as e:
|
|
321
|
+
SDKLogger.error(f"[Error] publish {command_name}: {e}")
|
|
322
|
+
return False
|
|
323
|
+
|
|
324
|
+
def _pub_switch_gait_by_name(self, gait_name: str) -> bool:
|
|
325
|
+
try:
|
|
326
|
+
msg = switchGaitByName()
|
|
327
|
+
msg.header.stamp = rospy.Time.now()
|
|
328
|
+
msg.gait_name = gait_name
|
|
329
|
+
self._pub_switch_gait.publish(msg)
|
|
330
|
+
# print(f"Published {gait_name} gait")
|
|
331
|
+
return True
|
|
332
|
+
except Exception as e:
|
|
333
|
+
SDKLogger.error(f"[Error] publish switch gait {gait_name}: {e}")
|
|
334
|
+
return False
|
|
335
|
+
|
|
336
|
+
def pub_walk_command(self) -> bool:
|
|
337
|
+
# return self._pub_joy_command(BUTTON_Y, "walk")
|
|
338
|
+
return self._pub_switch_gait_by_name("walk")
|
|
339
|
+
|
|
340
|
+
def pub_stance_command(self) -> bool:
|
|
341
|
+
try:
|
|
342
|
+
self.pub_cmd_vel(linear_x=0.0, linear_y=0.0, angular_z=0.0)
|
|
343
|
+
# return self._pub_joy_command(BUTTON_A, "stance")
|
|
344
|
+
return self._pub_switch_gait_by_name("stance")
|
|
345
|
+
except Exception as e:
|
|
346
|
+
SDKLogger.error(f"[Error] publish stance: {e}")
|
|
347
|
+
return False
|
|
348
|
+
|
|
349
|
+
def pub_trot_command(self) -> bool:
|
|
350
|
+
# return self._pub_joy_command(BUTTON_B, "trot")
|
|
351
|
+
return self._pub_switch_gait_by_name("walk")
|
|
352
|
+
|
|
353
|
+
def pub_step_ctrl(self, msg:footPoseTargetTrajectories)->bool:
|
|
354
|
+
try:
|
|
355
|
+
self._pub_step_ctrl.publish(msg)
|
|
356
|
+
return True
|
|
357
|
+
except Exception as e:
|
|
358
|
+
SDKLogger.error(f"[Error] publish step ctrl: {e}")
|
|
359
|
+
return False
|
|
360
|
+
|
|
361
|
+
"""
|
|
362
|
+
Kuavo Robot Arm IK&FK
|
|
363
|
+
"""
|
|
364
|
+
class KuavoRobotArmIKFK:
|
|
365
|
+
def __init__(self):
|
|
366
|
+
pass
|
|
367
|
+
def arm_ik(self,
|
|
368
|
+
left_pose: KuavoPose,
|
|
369
|
+
right_pose: KuavoPose,
|
|
370
|
+
left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
371
|
+
right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
372
|
+
arm_q0: list = None,
|
|
373
|
+
params: KuavoIKParams=None) -> list:
|
|
374
|
+
eef_pose_msg = twoArmHandPoseCmd()
|
|
375
|
+
if arm_q0 is None:
|
|
376
|
+
eef_pose_msg.joint_angles_as_q0 = False
|
|
377
|
+
else:
|
|
378
|
+
eef_pose_msg.joint_angles_as_q0 = True
|
|
379
|
+
eef_pose_msg.joint_angles = arm_q0
|
|
380
|
+
|
|
381
|
+
if params is None:
|
|
382
|
+
eef_pose_msg.use_custom_ik_param = False
|
|
383
|
+
else:
|
|
384
|
+
eef_pose_msg.use_custom_ik_param = True
|
|
385
|
+
eef_pose_msg.ik_param.major_optimality_tol = params.major_optimality_tol
|
|
386
|
+
eef_pose_msg.ik_param.major_feasibility_tol = params.major_feasibility_tol
|
|
387
|
+
eef_pose_msg.ik_param.minor_feasibility_tol = params.minor_feasibility_tol
|
|
388
|
+
eef_pose_msg.ik_param.major_iterations_limit = params.major_iterations_limit
|
|
389
|
+
eef_pose_msg.ik_param.oritation_constraint_tol= params.oritation_constraint_tol
|
|
390
|
+
eef_pose_msg.ik_param.pos_constraint_tol = params.pos_constraint_tol
|
|
391
|
+
eef_pose_msg.ik_param.pos_cost_weight = params.pos_cost_weight
|
|
392
|
+
|
|
393
|
+
# left hand
|
|
394
|
+
eef_pose_msg.hand_poses.left_pose.pos_xyz = left_pose.position
|
|
395
|
+
eef_pose_msg.hand_poses.left_pose.quat_xyzw = left_pose.orientation
|
|
396
|
+
eef_pose_msg.hand_poses.left_pose.elbow_pos_xyz = left_elbow_pos_xyz
|
|
397
|
+
|
|
398
|
+
# right hand
|
|
399
|
+
eef_pose_msg.hand_poses.right_pose.pos_xyz = right_pose.position
|
|
400
|
+
eef_pose_msg.hand_poses.right_pose.quat_xyzw = right_pose.orientation
|
|
401
|
+
eef_pose_msg.hand_poses.right_pose.elbow_pos_xyz = right_elbow_pos_xyz
|
|
402
|
+
|
|
403
|
+
return self._srv_arm_ik(eef_pose_msg)
|
|
404
|
+
|
|
405
|
+
def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
|
|
406
|
+
return self._srv_arm_fk(q)
|
|
407
|
+
|
|
408
|
+
def _srv_arm_ik(self, eef_pose_msg:twoArmHandPoseCmd)->list:
|
|
409
|
+
try:
|
|
410
|
+
rospy.wait_for_service('/ik/two_arm_hand_pose_cmd_srv',timeout=1.0)
|
|
411
|
+
ik_srv = rospy.ServiceProxy('/ik/two_arm_hand_pose_cmd_srv', twoArmHandPoseCmdSrv)
|
|
412
|
+
res = ik_srv(eef_pose_msg)
|
|
413
|
+
# print(eef_pose_msg)
|
|
414
|
+
if res.success:
|
|
415
|
+
return res.hand_poses.left_pose.joint_angles + res.hand_poses.right_pose.joint_angles
|
|
416
|
+
else:
|
|
417
|
+
return None
|
|
418
|
+
except rospy.ServiceException as e:
|
|
419
|
+
print("Service call failed: %s"%e)
|
|
420
|
+
return None
|
|
421
|
+
except Exception as e:
|
|
422
|
+
print(f"Failed to call ik/fk_srv: {e}")
|
|
423
|
+
return None
|
|
424
|
+
def _srv_arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
|
|
425
|
+
try:
|
|
426
|
+
rospy.wait_for_service('/ik/fk_srv',timeout=1.0)
|
|
427
|
+
ik_srv = rospy.ServiceProxy('/ik/fk_srv', fkSrv)
|
|
428
|
+
res = ik_srv(q)
|
|
429
|
+
if res.success:
|
|
430
|
+
return KuavoPose(position=res.hand_poses.left_pose.pos_xyz, orientation=res.hand_poses.left_pose.quat_xyzw), \
|
|
431
|
+
KuavoPose(position=res.hand_poses.right_pose.pos_xyz, orientation=res.hand_poses.right_pose.quat_xyzw),
|
|
432
|
+
else:
|
|
433
|
+
return None
|
|
434
|
+
except rospy.ServiceException as e:
|
|
435
|
+
print("Service call failed: %s"%e)
|
|
436
|
+
return None
|
|
437
|
+
except Exception as e:
|
|
438
|
+
print(f"Failed to call ik/fk_srv: {e}")
|
|
439
|
+
return None
|
|
440
|
+
"""
|
|
441
|
+
Kuavo Robot Control
|
|
442
|
+
"""
|
|
443
|
+
class KuavoRobotControl:
|
|
444
|
+
_instance = None
|
|
445
|
+
|
|
446
|
+
def __new__(cls, *args, **kwargs):
|
|
447
|
+
if not cls._instance:
|
|
448
|
+
cls._instance = super().__new__(cls)
|
|
449
|
+
if not rospy.core.is_initialized():
|
|
450
|
+
if not rospy.get_node_uri():
|
|
451
|
+
rospy.init_node(f'kuavo_sdk_node_{os.getpid()}', anonymous=True, disable_signals=True)
|
|
452
|
+
return cls._instance
|
|
453
|
+
|
|
454
|
+
def __init__(self):
|
|
455
|
+
if not hasattr(self, '_initialized'):
|
|
456
|
+
self._initialized = True
|
|
457
|
+
self.kuavo_eef_control = None
|
|
458
|
+
self.kuavo_head_control = ControlRobotHead()
|
|
459
|
+
self.kuavo_arm_control = ControlRobotArm()
|
|
460
|
+
self.kuavo_motion_control = ControlRobotMotion()
|
|
461
|
+
self.kuavo_arm_ik_fk = KuavoRobotArmIKFK()
|
|
462
|
+
# SDKLogger.debug("KuavoRobotControl initialized.")
|
|
463
|
+
|
|
464
|
+
def initialize(self, eef_type:str=None, debug:bool=False, timeout:float=1.0)-> Tuple[bool, str]:
|
|
465
|
+
# init eef control
|
|
466
|
+
if eef_type is None:
|
|
467
|
+
self.kuavo_eef_control = None
|
|
468
|
+
else:
|
|
469
|
+
self.kuavo_eef_control = ControlEndEffector(eef_type=eef_type)
|
|
470
|
+
|
|
471
|
+
connect_success = True
|
|
472
|
+
err_msg = ''
|
|
473
|
+
if not self.kuavo_arm_control.connect(timeout):
|
|
474
|
+
connect_success = False
|
|
475
|
+
err_msg = "Failed to connect to arm control topics, \n"
|
|
476
|
+
if not self.kuavo_head_control.connect(timeout):
|
|
477
|
+
connect_success = False
|
|
478
|
+
err_msg += "Failed to connect to head control topics, \n"
|
|
479
|
+
if not self.kuavo_motion_control.connect(timeout):
|
|
480
|
+
err_msg += "Failed to connect to motion control topics, \n"
|
|
481
|
+
connect_success = False
|
|
482
|
+
|
|
483
|
+
if self.kuavo_eef_control is not None and not self.kuavo_eef_control.connect(timeout):
|
|
484
|
+
connect_success = False
|
|
485
|
+
err_msg += "Failed to connect to end effector control topics."
|
|
486
|
+
|
|
487
|
+
if connect_success:
|
|
488
|
+
err_msg = 'success'
|
|
489
|
+
return connect_success, err_msg
|
|
490
|
+
|
|
491
|
+
""" End Effector Control"""
|
|
492
|
+
def control_robot_dexhand(self, left_position:list, right_position:list)->bool:
|
|
493
|
+
"""
|
|
494
|
+
Control robot dexhand
|
|
495
|
+
Args:
|
|
496
|
+
left_position: list of 6 floats between 0 and 100
|
|
497
|
+
right_position: list of 6 floats between 0 and 100
|
|
498
|
+
"""
|
|
499
|
+
if self.kuavo_eef_control is None:
|
|
500
|
+
SDKLogger.error("End effector control is not initialized.")
|
|
501
|
+
return False
|
|
502
|
+
|
|
503
|
+
if len(left_position) != 6 or len(right_position) != 6:
|
|
504
|
+
raise ValueError("Position lists must have a length of 6.")
|
|
505
|
+
|
|
506
|
+
for position in left_position + right_position:
|
|
507
|
+
if position < 0.0 or position > 100.0:
|
|
508
|
+
raise ValueError("All position values must be in the range [0.0, 100.0].")
|
|
509
|
+
|
|
510
|
+
SDKLogger.debug(f"Control robot dexhand: {left_position}, {right_position}")
|
|
511
|
+
return self.kuavo_eef_control.pub_control_robot_dexhand(left_position, right_position)
|
|
512
|
+
|
|
513
|
+
def execute_gesture(self, gestures:list)->bool:
|
|
514
|
+
"""
|
|
515
|
+
Execute gestures
|
|
516
|
+
Arguments:
|
|
517
|
+
- gestures: list of dicts with keys 'gesture_name' and 'hand_side'
|
|
518
|
+
e.g. [{'gesture_name': 'fist', 'hand_side': 0},]
|
|
519
|
+
"""
|
|
520
|
+
if self.kuavo_eef_control is None:
|
|
521
|
+
SDKLogger.warn("End effectors control is not initialized.")
|
|
522
|
+
return False
|
|
523
|
+
return self.kuavo_eef_control.srv_execute_gesture(gestures)
|
|
524
|
+
|
|
525
|
+
def get_gesture_names(self)->list:
|
|
526
|
+
"""
|
|
527
|
+
Get the names of all gestures.
|
|
528
|
+
"""
|
|
529
|
+
if self.kuavo_eef_control is None:
|
|
530
|
+
SDKLogger.warn("End effectors control is not initialized.")
|
|
531
|
+
return []
|
|
532
|
+
return self.kuavo_eef_control.srv_get_gesture_names()
|
|
533
|
+
|
|
534
|
+
def control_leju_claw(self, postions:list, velocities:list=[90, 90], torques:list=[1.0, 1.0]) ->bool:
|
|
535
|
+
"""
|
|
536
|
+
Control leju claw
|
|
537
|
+
Arguments:
|
|
538
|
+
- postions: list of positions for left and right claw
|
|
539
|
+
- velocities: list of velocities for left and right claw
|
|
540
|
+
- torques: list of torques for left and right claw
|
|
541
|
+
"""
|
|
542
|
+
if self.kuavo_eef_control is None:
|
|
543
|
+
SDKLogger.warn("End effectors control is not initialized.")
|
|
544
|
+
return False
|
|
545
|
+
SDKLogger.debug(f"Control leju claw: {postions}, {velocities}, {torques}")
|
|
546
|
+
if len(postions) != 2 or len(velocities) != 2 or len(torques) != 2:
|
|
547
|
+
raise ValueError("Position, velocity, and torque lists must have a length of 2.")
|
|
548
|
+
return self.kuavo_eef_control.srv_control_leju_claw(postions, velocities, torques)
|
|
549
|
+
"""--------------------------------------------------------------------------------------------"""
|
|
550
|
+
def control_robot_head(self, yaw:float, pitch:float)->bool:
|
|
551
|
+
"""
|
|
552
|
+
Control robot head
|
|
553
|
+
Arguments:
|
|
554
|
+
- yaw: yaw angle, radian
|
|
555
|
+
- pitch: pitch angle, radian
|
|
556
|
+
"""
|
|
557
|
+
SDKLogger.debug(f"Control robot head: {yaw}, {pitch}")
|
|
558
|
+
return self.kuavo_head_control.pub_control_robot_head(yaw, pitch)
|
|
559
|
+
|
|
560
|
+
|
|
561
|
+
def control_robot_arm_traj(self, joint_data:list)->bool:
|
|
562
|
+
"""
|
|
563
|
+
Control robot arm trajectory
|
|
564
|
+
Arguments:
|
|
565
|
+
- joint_data: list of joint data (degrees)
|
|
566
|
+
"""
|
|
567
|
+
# SDKLogger.debug(f"[ROS] Control robot arm trajectory: {joint_data}")
|
|
568
|
+
return self.kuavo_arm_control.pub_control_robot_arm_traj(joint_data)
|
|
569
|
+
|
|
570
|
+
def control_robot_arm_target_poses(self, times:list, joint_q:list)->bool:
|
|
571
|
+
"""
|
|
572
|
+
Control robot arm target poses
|
|
573
|
+
Arguments:
|
|
574
|
+
- times: list of times (seconds)
|
|
575
|
+
- joint_q: list of joint data (degrees)
|
|
576
|
+
"""
|
|
577
|
+
if len(times) != len(joint_q):
|
|
578
|
+
raise ValueError("Times and joint_q must have the same length.")
|
|
579
|
+
elif len(times) == 0:
|
|
580
|
+
raise ValueError("Times and joint_q must not be empty.")
|
|
581
|
+
|
|
582
|
+
return self.kuavo_arm_control.pub_arm_target_poses(times=times, joint_q=joint_q)
|
|
583
|
+
|
|
584
|
+
def change_robot_arm_ctrl_mode(self, mode:KuavoArmCtrlMode)->bool:
|
|
585
|
+
"""
|
|
586
|
+
Change robot arm control mode
|
|
587
|
+
Arguments:
|
|
588
|
+
- mode: arm control mode
|
|
589
|
+
"""
|
|
590
|
+
SDKLogger.debug(f"[ROS] Change robot arm control mode: {mode}")
|
|
591
|
+
return self.kuavo_arm_control.srv_change_arm_ctrl_mode(mode)
|
|
592
|
+
|
|
593
|
+
def get_robot_arm_ctrl_mode(self)->int:
|
|
594
|
+
"""
|
|
595
|
+
Get robot arm control mode
|
|
596
|
+
"""
|
|
597
|
+
return self.kuavo_arm_control.srv_get_arm_ctrl_mode()
|
|
598
|
+
|
|
599
|
+
def arm_ik(self, left_pose: KuavoPose, right_pose: KuavoPose,
|
|
600
|
+
left_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
601
|
+
right_elbow_pos_xyz: list = [0.0, 0.0, 0.0],
|
|
602
|
+
arm_q0: list = None, params: KuavoIKParams=None) -> list:
|
|
603
|
+
return self.kuavo_arm_ik_fk.arm_ik(left_pose, right_pose, left_elbow_pos_xyz, right_elbow_pos_xyz, arm_q0, params)
|
|
604
|
+
|
|
605
|
+
|
|
606
|
+
def arm_fk(self, q: list) -> Tuple[KuavoPose, KuavoPose]:
|
|
607
|
+
return self.kuavo_arm_ik_fk.arm_fk(q)
|
|
608
|
+
|
|
609
|
+
""" Motion """
|
|
610
|
+
def robot_stance(self)->bool:
|
|
611
|
+
return self.kuavo_motion_control.pub_stance_command()
|
|
612
|
+
|
|
613
|
+
def robot_trot(self)->bool:
|
|
614
|
+
return self.kuavo_motion_control.pub_trot_command()
|
|
615
|
+
|
|
616
|
+
def robot_walk(self, linear_x:float, linear_y:float, angular_z:float)->bool:
|
|
617
|
+
return self.kuavo_motion_control.pub_cmd_vel(linear_x, linear_y, angular_z)
|
|
618
|
+
|
|
619
|
+
def control_torso_height(self, height:float, pitch:float=0.0)->bool:
|
|
620
|
+
com_msg = Twist()
|
|
621
|
+
com_msg.linear.z = height
|
|
622
|
+
com_msg.angular.y = pitch
|
|
623
|
+
return self.kuavo_motion_control.pub_cmd_pose(com_msg)
|
|
624
|
+
|
|
625
|
+
def step_control(self, body_poses:list, dt:float, is_left_first_default:bool=True, collision_check:bool=True)->bool:
|
|
626
|
+
"""
|
|
627
|
+
Step control
|
|
628
|
+
Arguments:
|
|
629
|
+
- body_poses: list of body poses (x, y, z, yaw), meters and degrees
|
|
630
|
+
- dt: time step (seconds)
|
|
631
|
+
- is_left_first_default: whether to start with left foot
|
|
632
|
+
- collision_check: whether to check for collisions
|
|
633
|
+
"""
|
|
634
|
+
if len(body_poses) == 0:
|
|
635
|
+
raise ValueError("Body poses must not be empty.")
|
|
636
|
+
if dt <= 0.0:
|
|
637
|
+
raise ValueError("Time step must be greater than 0.0.")
|
|
638
|
+
for bp in body_poses:
|
|
639
|
+
if len(bp) != 4:
|
|
640
|
+
raise ValueError("Body pose must have 4 elements: [x, y, z, yaw]")
|
|
641
|
+
|
|
642
|
+
msg = get_multiple_steps_msg(body_poses, dt, is_left_first_default, collision_check)
|
|
643
|
+
return self.kuavo_motion_control.pub_step_ctrl(msg)
|
|
644
|
+
""" ------------------------------------------------------------------------------"""
|
|
645
|
+
def euler_to_rotation_matrix(yaw, pitch, roll):
|
|
646
|
+
# 计算各轴的旋转矩阵
|
|
647
|
+
R_yaw = np.array([[np.cos(yaw), -np.sin(yaw), 0],
|
|
648
|
+
[np.sin(yaw), np.cos(yaw), 0],
|
|
649
|
+
[0, 0, 1]])
|
|
650
|
+
|
|
651
|
+
R_pitch = np.array([[np.cos(pitch), 0, np.sin(pitch)],
|
|
652
|
+
[0, 1, 0],
|
|
653
|
+
[-np.sin(pitch), 0, np.cos(pitch)]])
|
|
654
|
+
|
|
655
|
+
R_roll = np.array([[1, 0, 0],
|
|
656
|
+
[0, np.cos(roll), -np.sin(roll)],
|
|
657
|
+
[0, np.sin(roll), np.cos(roll)]])
|
|
658
|
+
|
|
659
|
+
# 按照 Yaw-Pitch-Roll 的顺序组合旋转矩阵
|
|
660
|
+
R = np.dot(R_roll, np.dot(R_pitch, R_yaw))
|
|
661
|
+
return R
|
|
662
|
+
|
|
663
|
+
def get_foot_pose_traj_msg(time_traj:list, foot_idx_traj:list, foot_traj:list, torso_traj:list):
|
|
664
|
+
num = len(time_traj)
|
|
665
|
+
|
|
666
|
+
# 创建消息实例
|
|
667
|
+
msg = footPoseTargetTrajectories()
|
|
668
|
+
msg.timeTrajectory = time_traj # 设置时间轨迹
|
|
669
|
+
msg.footIndexTrajectory = foot_idx_traj # 设置脚索引
|
|
670
|
+
msg.footPoseTrajectory = [] # 初始化脚姿态轨迹
|
|
671
|
+
|
|
672
|
+
for i in range(num):
|
|
673
|
+
foot_pose_msg = footPose()
|
|
674
|
+
foot_pose_msg.footPose = foot_traj[i] # 设置脚姿态
|
|
675
|
+
foot_pose_msg.torsoPose = torso_traj[i] # 设置躯干姿态
|
|
676
|
+
msg.footPoseTrajectory.append(foot_pose_msg)
|
|
677
|
+
|
|
678
|
+
return msg
|
|
679
|
+
|
|
680
|
+
def generate_steps(torso_pos, torso_yaw, foot_bias):
|
|
681
|
+
l_foot_bias = np.array([0, foot_bias, -torso_pos[2]])
|
|
682
|
+
r_foot_bias = np.array([0, -foot_bias, -torso_pos[2]])
|
|
683
|
+
R_z = np.array([
|
|
684
|
+
[np.cos(torso_yaw), -np.sin(torso_yaw), 0],
|
|
685
|
+
[np.sin(torso_yaw), np.cos(torso_yaw), 0],
|
|
686
|
+
[0, 0, 1]
|
|
687
|
+
])
|
|
688
|
+
l_foot = torso_pos + R_z.dot(l_foot_bias)
|
|
689
|
+
r_foot = torso_pos + R_z.dot(r_foot_bias)
|
|
690
|
+
return l_foot, r_foot
|
|
691
|
+
|
|
692
|
+
def get_multiple_steps_msg(body_poses:list, dt:float, is_left_first:bool=True, collision_check:bool=True):
|
|
693
|
+
num_steps = 2*len(body_poses)
|
|
694
|
+
time_traj = []
|
|
695
|
+
foot_idx_traj = []
|
|
696
|
+
foot_traj = []
|
|
697
|
+
torso_traj = []
|
|
698
|
+
l_foot_rect_last = RotatingRectangle(center=(0, 0.1), width=0.24, height=0.1, angle=0)
|
|
699
|
+
r_foot_rect_last = RotatingRectangle(center=(0,-0.1), width=0.24, height=0.1, angle=0)
|
|
700
|
+
torso_pose_last = np.array([0, 0, 0, 0])
|
|
701
|
+
for i in range(num_steps):
|
|
702
|
+
time_traj.append(dt * (i+1))
|
|
703
|
+
body_pose = body_poses[i//2]
|
|
704
|
+
torso_pos = np.asarray(body_pose[:3])
|
|
705
|
+
torso_yaw = np.radians(body_pose[3])
|
|
706
|
+
l_foot, r_foot = generate_steps(torso_pos, torso_yaw, 0.1)
|
|
707
|
+
l_foot = [*l_foot[:3], torso_yaw]
|
|
708
|
+
r_foot = [*r_foot[:3], torso_yaw]
|
|
709
|
+
|
|
710
|
+
if(i%2 == 0):
|
|
711
|
+
torso_pose = np.array([*body_pose[:3], torso_yaw])
|
|
712
|
+
R_wl = euler_to_rotation_matrix(torso_pose_last[3], 0, 0)
|
|
713
|
+
delta_pos = R_wl.T @ (torso_pose[:3] - torso_pose_last[:3])
|
|
714
|
+
# print("delta_pos:", delta_pos)
|
|
715
|
+
if(torso_yaw > 0.0 or delta_pos[1] > 0.0):
|
|
716
|
+
is_left_first = True
|
|
717
|
+
else:
|
|
718
|
+
is_left_first = False
|
|
719
|
+
|
|
720
|
+
if(collision_check and i%2 == 0):
|
|
721
|
+
l_foot_rect_next = RotatingRectangle(center=(l_foot[0],l_foot[1]), width=0.24, height=0.1, angle=torso_yaw)
|
|
722
|
+
r_foot_rect_next = RotatingRectangle(center=(r_foot[0],r_foot[1]), width=0.24, height=0.1, angle=torso_yaw)
|
|
723
|
+
l_collision = l_foot_rect_next.is_collision(r_foot_rect_last)
|
|
724
|
+
r_collision = r_foot_rect_next.is_collision(l_foot_rect_last)
|
|
725
|
+
if l_collision and r_collision:
|
|
726
|
+
SDKLogger.error("[Control] Detect collision, Please adjust your body_poses input!!!")
|
|
727
|
+
break
|
|
728
|
+
elif l_collision:
|
|
729
|
+
SDKLogger.warn("[Control] Left foot is in collision, switch to right foot")
|
|
730
|
+
is_left_first = False
|
|
731
|
+
elif r_collision:
|
|
732
|
+
SDKLogger.warn("[Control] Right foot is in collision, switch to left foot")
|
|
733
|
+
is_left_first = True
|
|
734
|
+
l_foot_rect_last = l_foot_rect_next
|
|
735
|
+
r_foot_rect_last = r_foot_rect_next
|
|
736
|
+
if(i%2 == 0):
|
|
737
|
+
torso_traj.append((torso_pose_last + torso_pose)/2.0)
|
|
738
|
+
if is_left_first:
|
|
739
|
+
foot_idx_traj.append(0)
|
|
740
|
+
foot_traj.append(l_foot)
|
|
741
|
+
else:
|
|
742
|
+
foot_idx_traj.append(1)
|
|
743
|
+
foot_traj.append(r_foot)
|
|
744
|
+
else:
|
|
745
|
+
torso_traj.append(torso_pose)
|
|
746
|
+
if is_left_first:
|
|
747
|
+
foot_idx_traj.append(1)
|
|
748
|
+
foot_traj.append(r_foot)
|
|
749
|
+
else:
|
|
750
|
+
foot_idx_traj.append(0)
|
|
751
|
+
foot_traj.append(l_foot)
|
|
752
|
+
torso_pose_last = torso_traj[-1]
|
|
753
|
+
# print("time_traj:", time_traj)
|
|
754
|
+
# print("foot_idx_traj:", foot_idx_traj)
|
|
755
|
+
# print("foot_traj:", foot_traj)
|
|
756
|
+
# print("torso_traj:", torso_traj)
|
|
757
|
+
return get_foot_pose_traj_msg(time_traj, foot_idx_traj, foot_traj, torso_traj)
|
|
758
|
+
""" ------------------------------------------------------------------------------"""
|