kuavo-humanoid-sdk 1.2.2b3208__20250922170818-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 +6 -0
- kuavo_humanoid_sdk/common/logger.py +45 -0
- kuavo_humanoid_sdk/interfaces/__init__.py +4 -0
- kuavo_humanoid_sdk/interfaces/data_types.py +288 -0
- kuavo_humanoid_sdk/interfaces/end_effector.py +62 -0
- kuavo_humanoid_sdk/interfaces/robot.py +22 -0
- kuavo_humanoid_sdk/interfaces/robot_info.py +56 -0
- kuavo_humanoid_sdk/kuavo/__init__.py +16 -0
- kuavo_humanoid_sdk/kuavo/core/audio.py +32 -0
- kuavo_humanoid_sdk/kuavo/core/core.py +666 -0
- kuavo_humanoid_sdk/kuavo/core/dex_hand_control.py +114 -0
- kuavo_humanoid_sdk/kuavo/core/leju_claw_control.py +67 -0
- kuavo_humanoid_sdk/kuavo/core/llm_doubao.py +608 -0
- kuavo_humanoid_sdk/kuavo/core/microphone.py +192 -0
- kuavo_humanoid_sdk/kuavo/core/navigation.py +70 -0
- kuavo_humanoid_sdk/kuavo/core/ros/audio.py +110 -0
- kuavo_humanoid_sdk/kuavo/core/ros/camera.py +105 -0
- kuavo_humanoid_sdk/kuavo/core/ros/control.py +1524 -0
- kuavo_humanoid_sdk/kuavo/core/ros/microphone.py +38 -0
- kuavo_humanoid_sdk/kuavo/core/ros/navigation.py +217 -0
- kuavo_humanoid_sdk/kuavo/core/ros/observation.py +94 -0
- kuavo_humanoid_sdk/kuavo/core/ros/param.py +201 -0
- kuavo_humanoid_sdk/kuavo/core/ros/sat_utils.py +103 -0
- kuavo_humanoid_sdk/kuavo/core/ros/state.py +652 -0
- kuavo_humanoid_sdk/kuavo/core/ros/tools.py +220 -0
- kuavo_humanoid_sdk/kuavo/core/ros/vision.py +234 -0
- kuavo_humanoid_sdk/kuavo/core/ros_env.py +238 -0
- kuavo_humanoid_sdk/kuavo/core/sdk_deprecated.py +41 -0
- kuavo_humanoid_sdk/kuavo/demo_climbstair.py +249 -0
- kuavo_humanoid_sdk/kuavo/dexterous_hand.py +238 -0
- kuavo_humanoid_sdk/kuavo/leju_claw.py +235 -0
- kuavo_humanoid_sdk/kuavo/logger_client.py +80 -0
- kuavo_humanoid_sdk/kuavo/robot.py +646 -0
- kuavo_humanoid_sdk/kuavo/robot_arm.py +411 -0
- kuavo_humanoid_sdk/kuavo/robot_audio.py +39 -0
- kuavo_humanoid_sdk/kuavo/robot_blockly.py +1154 -0
- kuavo_humanoid_sdk/kuavo/robot_climbstair.py +1607 -0
- kuavo_humanoid_sdk/kuavo/robot_head.py +95 -0
- kuavo_humanoid_sdk/kuavo/robot_info.py +134 -0
- kuavo_humanoid_sdk/kuavo/robot_microphone.py +19 -0
- kuavo_humanoid_sdk/kuavo/robot_navigation.py +135 -0
- kuavo_humanoid_sdk/kuavo/robot_observation.py +64 -0
- kuavo_humanoid_sdk/kuavo/robot_speech.py +24 -0
- kuavo_humanoid_sdk/kuavo/robot_state.py +310 -0
- kuavo_humanoid_sdk/kuavo/robot_tool.py +109 -0
- kuavo_humanoid_sdk/kuavo/robot_vision.py +81 -0
- kuavo_humanoid_sdk/kuavo_strategy/__init__.py +2 -0
- kuavo_humanoid_sdk/kuavo_strategy/grasp_box/grasp_box_strategy.py +1325 -0
- kuavo_humanoid_sdk/kuavo_strategy/kuavo_strategy.py +106 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/common/data_type.py +340 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/common/events/base_event.py +215 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/common/robot_sdk.py +25 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/case.py +331 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/pick_place_box/strategy.py +504 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/utils/logger_setup.py +40 -0
- kuavo_humanoid_sdk/kuavo_strategy_v2/utils/utils.py +88 -0
- kuavo_humanoid_sdk/msg/__init__.py +4 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/__init__.py +7 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetection.py +306 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AprilTagDetectionArray.py +437 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_AudioReceiverData.py +122 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_FTsensorData.py +260 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_JoySticks.py +191 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_Metadata.py +199 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_MmDetectionMsg.py +264 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_RobotActionState.py +112 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TFArray.py +323 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_TaskPoint.py +175 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/__init__.py +62 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armCollisionCheckInfo.py +160 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPose.py +161 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armHandPoseFree.py +171 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armPoseWithTimeStamp.py +168 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_armTargetPoses.py +171 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_bezierCurveCubicPoint.py +178 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandCommand.py +229 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_dexhandTouchState.py +256 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_endEffectorData.py +227 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose.py +123 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6D.py +123 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPose6DTargetTrajectories.py +320 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseTargetTrajectories.py +301 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVision.py +136 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoseWithVisionArray.py +231 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses.py +149 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_footPoses6D.py +149 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_fullBodyTargetTrajectories.py +258 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gaitTimeName.py +147 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureInfo.py +218 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_gestureTask.py +149 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_handPose.py +136 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_headBodyPose.py +145 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveError.py +171 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_ikSolveParam.py +140 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_imuData.py +165 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointBezierTrajectory.py +201 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointCmd.py +390 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_jointData.py +205 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_kuavoModeSchedule.py +224 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawCommand.py +320 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_lejuClawState.py +341 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_motorParam.py +122 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfo.py +143 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_picoPoseInfoList.py +220 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_planArmState.py +120 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_qv.py +121 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotArmQVVD.py +177 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotBodyMatrices.py +332 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHandPosition.py +225 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotHeadMotionData.py +128 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_robotState.py +222 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_sensorsData.py +655 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_switchGaitByName.py +200 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_tagDataArray.py +216 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_touchSensorStatus.py +162 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPose.py +273 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmd.py +316 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseCmdFree.py +338 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_twoArmHandPoseFree.py +299 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloDetection.py +251 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/msg/_yoloOutputData.py +168 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_CreatePath.py +581 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_ExecuteArmAction.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetAllMaps.py +241 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetCurrentMap.py +225 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_GetTargetPartPoseInCamera.py +298 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_InitialPoseWithTaskPoint.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_LoadMap.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_NavigateToTaskPoint.py +281 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_RepublishTFs.py +373 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetInitialPose.py +394 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetJoyTopic.py +282 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode.py +468 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SetLEDMode_free.py +289 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_SpeechSynthesis.py +270 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_TaskPointOperation.py +536 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/__init__.py +43 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_adjustZeroPoint.py +277 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlMode.py +275 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeArmCtrlModeKuavo.py +236 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeMotorParam.py +299 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_changeTorsoCtrlMode.py +274 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_controlLejuClaw.py +408 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_enableHandTouchSensor.py +304 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_fkSrv.py +395 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPose6DTargetTrajectoriesSrv.py +426 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_footPoseTargetTrajectoriesSrv.py +409 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecute.py +339 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureExecuteState.py +257 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_gestureList.py +418 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getCurrentGaitName.py +253 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorParam.py +299 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_getMotorZeroPoints.py +286 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_handForceLevel.py +330 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_jointMoveTo.py +302 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryBezierCurve.py +422 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_planArmTrajectoryCubicSpline.py +490 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_playmusic.py +268 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setHwIntialState.py +304 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMmCtrlFrame.py +273 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setMotorEncoderRoundService.py +283 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_setTagId.py +275 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_singleStepControl.py +444 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdFreeSrv.py +716 -0
- kuavo_humanoid_sdk/msg/kuavo_msgs/srv/_twoArmHandPoseCmdSrv.py +664 -0
- kuavo_humanoid_sdk/msg/motion_capture_ik/__init__.py +7 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/__init__.py +7 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/__init__.py +12 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_constraint.py +142 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_controller_data.py +121 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_lagrangian_metrics.py +148 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mode_schedule.py +150 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_flattened_controller.py +666 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_input.py +122 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_observation.py +209 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_performance_indices.py +140 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_solver_data.py +886 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_state.py +122 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_mpc_target_trajectories.py +239 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/msg/_multiplier.py +148 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/srv/__init__.py +1 -0
- kuavo_humanoid_sdk/msg/ocs2_msgs/srv/_reset.py +376 -0
- kuavo_humanoid_sdk-1.2.2b3208.dist-info/METADATA +297 -0
- kuavo_humanoid_sdk-1.2.2b3208.dist-info/RECORD +186 -0
- kuavo_humanoid_sdk-1.2.2b3208.dist-info/WHEEL +6 -0
- kuavo_humanoid_sdk-1.2.2b3208.dist-info/top_level.txt +1 -0
|
@@ -0,0 +1,652 @@
|
|
|
1
|
+
import time
|
|
2
|
+
from typing import Tuple
|
|
3
|
+
import copy
|
|
4
|
+
import rospy
|
|
5
|
+
from std_msgs.msg import Float64
|
|
6
|
+
from nav_msgs.msg import Odometry
|
|
7
|
+
from std_srvs.srv import SetBool, SetBoolRequest
|
|
8
|
+
from sensor_msgs.msg import JointState
|
|
9
|
+
from kuavo_humanoid_sdk.msg.kuavo_msgs.msg import sensorsData, lejuClawState, gaitTimeName, dexhandTouchState
|
|
10
|
+
from kuavo_msgs.srv import changeArmCtrlMode, changeArmCtrlModeRequest, getCurrentGaitName, getCurrentGaitNameRequest,gestureExecuteState, gestureExecuteStateRequest
|
|
11
|
+
from kuavo_humanoid_sdk.msg.ocs2_msgs.msg import mpc_observation
|
|
12
|
+
from kuavo_humanoid_sdk.msg.kuavo_msgs.srv import (changeArmCtrlMode, changeArmCtrlModeRequest,setMmCtrlFrame, setMmCtrlFrameRequest, changeTorsoCtrlMode, changeTorsoCtrlModeRequest)
|
|
13
|
+
from collections import deque
|
|
14
|
+
from typing import Tuple
|
|
15
|
+
import copy
|
|
16
|
+
from kuavo_humanoid_sdk.common.logger import SDKLogger
|
|
17
|
+
from kuavo_humanoid_sdk.kuavo.core.ros.param import make_robot_param, EndEffectorType
|
|
18
|
+
from kuavo_humanoid_sdk.interfaces.data_types import (KuavoImuData, KuavoJointData, KuavoOdometry, KuavoManipulationMpcFrame,
|
|
19
|
+
KuavoArmCtrlMode, EndEffectorState, KuavoDexHandTouchState,
|
|
20
|
+
KuavoManipulationMpcCtrlMode, KuavoManipulationMpcControlFlow)
|
|
21
|
+
class GaitManager:
|
|
22
|
+
def __init__(self, max_size: int = 20):
|
|
23
|
+
self._max_size = max_size
|
|
24
|
+
self._gait_time_names = deque(maxlen=max_size)
|
|
25
|
+
|
|
26
|
+
@property
|
|
27
|
+
def is_empty(self) -> bool:
|
|
28
|
+
"""Check if there are any gait time names stored.
|
|
29
|
+
|
|
30
|
+
Returns:
|
|
31
|
+
bool: True if no gait time names are stored, False otherwise
|
|
32
|
+
"""
|
|
33
|
+
return len(self._gait_time_names) == 0
|
|
34
|
+
def add(self, start_time: float, name: str) -> None:
|
|
35
|
+
self._gait_time_names.append((start_time, name))
|
|
36
|
+
|
|
37
|
+
def get_gait(self, current_time: float) -> str:
|
|
38
|
+
if not self._gait_time_names:
|
|
39
|
+
return "No_Gait"
|
|
40
|
+
|
|
41
|
+
for start_time, name in reversed(self._gait_time_names):
|
|
42
|
+
if current_time >= start_time:
|
|
43
|
+
return name
|
|
44
|
+
|
|
45
|
+
return self._gait_time_names[0].name
|
|
46
|
+
|
|
47
|
+
def get_gait_name(self, current_time: float) -> str:
|
|
48
|
+
return self.get_gait(current_time)[1]
|
|
49
|
+
|
|
50
|
+
def get_last_gait_name(self) -> str:
|
|
51
|
+
if not self._gait_time_names:
|
|
52
|
+
return "No_Gait"
|
|
53
|
+
return self._gait_time_names[-1][1]
|
|
54
|
+
|
|
55
|
+
|
|
56
|
+
class KuavoRobotStateCore:
|
|
57
|
+
_instance = None
|
|
58
|
+
|
|
59
|
+
def __new__(cls, *args, **kwargs):
|
|
60
|
+
if not cls._instance:
|
|
61
|
+
cls._instance = super().__new__(cls)
|
|
62
|
+
return cls._instance
|
|
63
|
+
|
|
64
|
+
def __init__(self):
|
|
65
|
+
if not hasattr(self, '_initialized'):
|
|
66
|
+
rospy.Subscriber("/sensors_data_raw", sensorsData, self._sensors_data_raw_callback)
|
|
67
|
+
rospy.Subscriber("/odom", Odometry, self._odom_callback)
|
|
68
|
+
rospy.Subscriber("/humanoid/mpc/terrainHeight", Float64, self._terrain_height_callback)
|
|
69
|
+
rospy.Subscriber("/humanoid_mpc_gait_time_name", gaitTimeName, self._humanoid_mpc_gait_changed_callback)
|
|
70
|
+
rospy.Subscriber("/humanoid_mpc_observation", mpc_observation, self._humanoid_mpc_observation_callback)
|
|
71
|
+
|
|
72
|
+
kuavo_info = make_robot_param()
|
|
73
|
+
self._ee_type = kuavo_info['end_effector_type']
|
|
74
|
+
if self._ee_type == EndEffectorType.LEJUCLAW:
|
|
75
|
+
rospy.Subscriber("/leju_claw_state", lejuClawState, self._lejuclaw_state_callback)
|
|
76
|
+
elif self._ee_type == EndEffectorType.QIANGNAO:
|
|
77
|
+
rospy.Subscriber("/dexhand/state", JointState, self._dexterous_hand_state_callback)
|
|
78
|
+
elif self._ee_type == EndEffectorType.QIANGNAO_TOUCH:
|
|
79
|
+
rospy.Subscriber("/dexhand/state", JointState, self._dexterous_hand_state_callback)
|
|
80
|
+
rospy.Subscriber("/dexhand/touch_state", dexhandTouchState, self._dexhand_touch_state_callback)
|
|
81
|
+
# Initialize touch state for both hands with empty KuavoDexHandTouchState instances
|
|
82
|
+
self._dexhand_touch_state = (
|
|
83
|
+
KuavoDexHandTouchState(
|
|
84
|
+
data=(KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
85
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
86
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
87
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
88
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0))
|
|
89
|
+
), # Left hand touch state
|
|
90
|
+
KuavoDexHandTouchState(
|
|
91
|
+
data=(KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
92
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
93
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
94
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0),
|
|
95
|
+
KuavoDexHandTouchState.KuavoTouchState(0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0))
|
|
96
|
+
) # Right hand touch state
|
|
97
|
+
)
|
|
98
|
+
|
|
99
|
+
""" data """
|
|
100
|
+
self._terrain_height = 0.0
|
|
101
|
+
self._imu_data = KuavoImuData(
|
|
102
|
+
gyro = (0.0, 0.0, 0.0),
|
|
103
|
+
acc = (0.0, 0.0, 0.0),
|
|
104
|
+
free_acc = (0.0, 0.0, 0.0),
|
|
105
|
+
quat = (0.0, 0.0, 0.0, 0.0)
|
|
106
|
+
)
|
|
107
|
+
self._joint_data = KuavoJointData(
|
|
108
|
+
position = [0.0] * 28,
|
|
109
|
+
velocity = [0.0] * 28,
|
|
110
|
+
torque = [0.0] * 28,
|
|
111
|
+
acceleration = [0.0] * 28
|
|
112
|
+
)
|
|
113
|
+
self._odom_data = KuavoOdometry(
|
|
114
|
+
position = (0.0, 0.0, 0.0),
|
|
115
|
+
orientation = (0.0, 0.0, 0.0, 0.0),
|
|
116
|
+
linear = (0.0, 0.0, 0.0),
|
|
117
|
+
angular = (0.0, 0.0, 0.0)
|
|
118
|
+
)
|
|
119
|
+
self._eef_state = (EndEffectorState(
|
|
120
|
+
position = [0.0] * 12 if kuavo_info['end_effector_type'] is not None and kuavo_info['end_effector_type'].startswith('qiangnao') else [0.0] * 2,
|
|
121
|
+
velocity = [0.0] * 12 if kuavo_info['end_effector_type'] is not None and kuavo_info['end_effector_type'].startswith('qiangnao') else [0.0] * 2,
|
|
122
|
+
effort = [0.0] * 12 if kuavo_info['end_effector_type'] is not None and kuavo_info['end_effector_type'].startswith('qiangnao') else [0.0] * 2,
|
|
123
|
+
state=EndEffectorState.GraspingState.UNKNOWN
|
|
124
|
+
), EndEffectorState(
|
|
125
|
+
position = [0.0] * 12 if kuavo_info['end_effector_type'] is not None and kuavo_info['end_effector_type'].startswith('qiangnao') else [0.0] * 2,
|
|
126
|
+
velocity = [0.0] * 12 if kuavo_info['end_effector_type'] is not None and kuavo_info['end_effector_type'].startswith('qiangnao') else [0.0] * 2,
|
|
127
|
+
effort = [0.0] * 12 if kuavo_info['end_effector_type'] is not None and kuavo_info['end_effector_type'].startswith('qiangnao') else [0.0] * 2,
|
|
128
|
+
state=EndEffectorState.GraspingState.UNKNOWN
|
|
129
|
+
))
|
|
130
|
+
|
|
131
|
+
# gait manager
|
|
132
|
+
self._gait_manager = GaitManager()
|
|
133
|
+
self._prev_gait_name = self.gait_name()
|
|
134
|
+
|
|
135
|
+
# Wait for first MPC observation data
|
|
136
|
+
self._mpc_observation_data = None
|
|
137
|
+
start_time = time.time()
|
|
138
|
+
while self._mpc_observation_data is None:
|
|
139
|
+
if time.time() - start_time > 1.0: # 1.0s timeout
|
|
140
|
+
SDKLogger.warn("Timeout waiting for MPC observation data")
|
|
141
|
+
break
|
|
142
|
+
SDKLogger.debug("Waiting for first MPC observation data...")
|
|
143
|
+
time.sleep(0.1)
|
|
144
|
+
# 如果 gait_manager 为空,则把当前的状态添加到其中
|
|
145
|
+
if self._mpc_observation_data is not None:
|
|
146
|
+
if self._gait_manager.is_empty:
|
|
147
|
+
self._prev_gait_name = self.gait_name()
|
|
148
|
+
SDKLogger.debug(f"[State] Adding initial gait state: {self._prev_gait_name} at time {self._mpc_observation_data.time}")
|
|
149
|
+
self._gait_manager.add(self._mpc_observation_data.time, self._prev_gait_name)
|
|
150
|
+
|
|
151
|
+
# 获取当前手臂控制模式
|
|
152
|
+
self._arm_ctrl_mode = self._srv_get_arm_ctrl_mode()
|
|
153
|
+
self._initialized = True
|
|
154
|
+
|
|
155
|
+
# 获取manipulation mpc 相关参数
|
|
156
|
+
self._manipulation_mpc_frame = self._srv_get_manipulation_mpc_frame()
|
|
157
|
+
self._manipulation_mpc_ctrl_mode = self._srv_get_manipulation_mpc_ctrl_mode()
|
|
158
|
+
self._manipulation_mpc_control_flow = self._srv_get_manipulation_mpc_control_flow()
|
|
159
|
+
|
|
160
|
+
@property
|
|
161
|
+
def com_height(self)->float:
|
|
162
|
+
# odom.position.z - terrain_height = com_height
|
|
163
|
+
return self._odom_data.position[2] - self._terrain_height
|
|
164
|
+
|
|
165
|
+
@property
|
|
166
|
+
def imu_data(self)->KuavoImuData:
|
|
167
|
+
return self._imu_data
|
|
168
|
+
|
|
169
|
+
@property
|
|
170
|
+
def joint_data(self)->KuavoJointData:
|
|
171
|
+
return self._joint_data
|
|
172
|
+
|
|
173
|
+
@property
|
|
174
|
+
def odom_data(self)->KuavoOdometry:
|
|
175
|
+
return self._odom_data
|
|
176
|
+
|
|
177
|
+
@property
|
|
178
|
+
def arm_control_mode(self) -> KuavoArmCtrlMode:
|
|
179
|
+
mode = self._srv_get_arm_ctrl_mode()
|
|
180
|
+
if mode is not None:
|
|
181
|
+
self._arm_ctrl_mode = mode
|
|
182
|
+
return self._arm_ctrl_mode
|
|
183
|
+
|
|
184
|
+
@property
|
|
185
|
+
def manipulation_mpc_ctrl_mode(self)->KuavoManipulationMpcCtrlMode:
|
|
186
|
+
mode = self._srv_get_manipulation_mpc_ctrl_mode()
|
|
187
|
+
if mode is not None:
|
|
188
|
+
self._manipulation_mpc_ctrl_mode = mode
|
|
189
|
+
return self._manipulation_mpc_ctrl_mode
|
|
190
|
+
|
|
191
|
+
@property
|
|
192
|
+
def manipulation_mpc_frame(self)->KuavoManipulationMpcFrame:
|
|
193
|
+
frame = self._srv_get_manipulation_mpc_frame()
|
|
194
|
+
if frame is not None:
|
|
195
|
+
self._manipulation_mpc_frame = frame
|
|
196
|
+
return self._manipulation_mpc_frame
|
|
197
|
+
|
|
198
|
+
@property
|
|
199
|
+
def manipulation_mpc_control_flow(self)->KuavoManipulationMpcControlFlow:
|
|
200
|
+
flow = self._srv_get_manipulation_mpc_control_flow()
|
|
201
|
+
if flow is not None:
|
|
202
|
+
self._manipulation_mpc_control_flow = flow
|
|
203
|
+
return self._manipulation_mpc_control_flow
|
|
204
|
+
|
|
205
|
+
@property
|
|
206
|
+
def pitch_limit_enabled(self)->bool:
|
|
207
|
+
success, status = self._srv_get_pitch_limit_status()
|
|
208
|
+
if success:
|
|
209
|
+
return not ('disabled' in status)
|
|
210
|
+
else:
|
|
211
|
+
return False
|
|
212
|
+
|
|
213
|
+
@property
|
|
214
|
+
def eef_state(self)->Tuple[EndEffectorState, EndEffectorState]:
|
|
215
|
+
return self._eef_state
|
|
216
|
+
|
|
217
|
+
@property
|
|
218
|
+
def dexhand_touch_state(self)-> Tuple[KuavoDexHandTouchState, KuavoDexHandTouchState]:
|
|
219
|
+
if self._ee_type != EndEffectorType.QIANGNAO_TOUCH:
|
|
220
|
+
raise Exception("This robot does not support touch state")
|
|
221
|
+
return self._dexhand_touch_state
|
|
222
|
+
|
|
223
|
+
@property
|
|
224
|
+
def current_observation_time(self) -> float:
|
|
225
|
+
"""Get the current observation time from MPC.
|
|
226
|
+
|
|
227
|
+
Returns:
|
|
228
|
+
float: Current observation time in seconds, or None if no observation data available
|
|
229
|
+
"""
|
|
230
|
+
if self._mpc_observation_data is None:
|
|
231
|
+
return None
|
|
232
|
+
return self._mpc_observation_data.time
|
|
233
|
+
|
|
234
|
+
@property
|
|
235
|
+
def current_gait_mode(self) -> int:
|
|
236
|
+
"""
|
|
237
|
+
Get the current gait mode from MPC observation.
|
|
238
|
+
|
|
239
|
+
Notes: FF=0, FH=1, FT=2, FS=3, HF=4, HH=5, HT=6, HS=7, TF=8, TH=9, TT=10, TS=11, SF=12, SH=13, ST=14, SS=15
|
|
240
|
+
|
|
241
|
+
Returns:
|
|
242
|
+
int: Current gait mode, or None if no observation data available
|
|
243
|
+
"""
|
|
244
|
+
if self._mpc_observation_data is None:
|
|
245
|
+
return None
|
|
246
|
+
return self._mpc_observation_data.mode
|
|
247
|
+
|
|
248
|
+
def gait_name(self)->str:
|
|
249
|
+
return self._srv_get_current_gait_name()
|
|
250
|
+
|
|
251
|
+
def is_gait(self, gait_name: str) -> bool:
|
|
252
|
+
"""Check if current gait matches the given gait name.
|
|
253
|
+
|
|
254
|
+
Args:
|
|
255
|
+
gait_name (str): Name of gait to check
|
|
256
|
+
|
|
257
|
+
Returns:
|
|
258
|
+
bool: True if current gait matches given name, False otherwise
|
|
259
|
+
"""
|
|
260
|
+
return self._gait_manager.get_gait(self._mpc_observation_data.time) == gait_name
|
|
261
|
+
|
|
262
|
+
def register_gait_changed_callback(self, callback):
|
|
263
|
+
"""Register a callback function that will be called when the gait changes.
|
|
264
|
+
|
|
265
|
+
Args:
|
|
266
|
+
callback: A function that takes current time (float) and gait name (str) as arguments
|
|
267
|
+
Raises:
|
|
268
|
+
ValueError: If callback does not accept 2 parameters: current_time (float), gait_name (str)
|
|
269
|
+
"""
|
|
270
|
+
if not hasattr(self, '_gait_changed_callbacks'):
|
|
271
|
+
self._gait_changed_callbacks = []
|
|
272
|
+
|
|
273
|
+
# Verify callback accepts current_time (float) and gait_name (str) parameters
|
|
274
|
+
from inspect import signature
|
|
275
|
+
sig = signature(callback)
|
|
276
|
+
if len(sig.parameters) != 2:
|
|
277
|
+
raise ValueError("Callback must accept 2 parameters: current_time (float), gait_name (str)")
|
|
278
|
+
if callback not in self._gait_changed_callbacks:
|
|
279
|
+
self._gait_changed_callbacks.append(callback)
|
|
280
|
+
|
|
281
|
+
""" ------------------------------- callback ------------------------------- """
|
|
282
|
+
def _terrain_height_callback(self, msg)->None:
|
|
283
|
+
self._terrain_height = msg.data
|
|
284
|
+
|
|
285
|
+
def _sensors_data_raw_callback(self, msg)->None:
|
|
286
|
+
# update imu data
|
|
287
|
+
self._imu_data = KuavoImuData(
|
|
288
|
+
gyro = (msg.imu_data.gyro.x, msg.imu_data.gyro.y, msg.imu_data.gyro.z),
|
|
289
|
+
acc = (msg.imu_data.acc.x, msg.imu_data.acc.y, msg.imu_data.acc.z),
|
|
290
|
+
free_acc = (msg.imu_data.free_acc.x, msg.imu_data.free_acc.y, msg.imu_data.free_acc.z),
|
|
291
|
+
quat = (msg.imu_data.quat.x, msg.imu_data.quat.y, msg.imu_data.quat.z, msg.imu_data.quat.w)
|
|
292
|
+
)
|
|
293
|
+
# update joint data
|
|
294
|
+
self._joint_data = KuavoJointData(
|
|
295
|
+
position = copy.deepcopy(msg.joint_data.joint_q),
|
|
296
|
+
velocity = copy.deepcopy(msg.joint_data.joint_v),
|
|
297
|
+
torque = copy.deepcopy(msg.joint_data.joint_vd),
|
|
298
|
+
acceleration = copy.deepcopy(msg.joint_data.joint_current if hasattr(msg.joint_data, 'joint_current') else msg.joint_data.joint_torque)
|
|
299
|
+
)
|
|
300
|
+
|
|
301
|
+
def _odom_callback(self, msg)->None:
|
|
302
|
+
# update odom data
|
|
303
|
+
self._odom_data = KuavoOdometry(
|
|
304
|
+
position = (msg.pose.pose.position.x, msg.pose.pose.position.y, msg.pose.pose.position.z),
|
|
305
|
+
orientation = (msg.pose.pose.orientation.x, msg.pose.pose.orientation.y, msg.pose.pose.orientation.z, msg.pose.pose.orientation.w),
|
|
306
|
+
linear = (msg.twist.twist.linear.x, msg.twist.twist.linear.y, msg.twist.twist.linear.z),
|
|
307
|
+
angular = (msg.twist.twist.angular.x, msg.twist.twist.angular.y, msg.twist.twist.angular.z)
|
|
308
|
+
)
|
|
309
|
+
|
|
310
|
+
def _lejuclaw_state_callback(self, msg)->None:
|
|
311
|
+
self._eef_state = (EndEffectorState(
|
|
312
|
+
# left claw
|
|
313
|
+
position = [msg.data.position[0]],
|
|
314
|
+
velocity = [msg.data.velocity[0]],
|
|
315
|
+
effort = [msg.data.effort[0]],
|
|
316
|
+
state=EndEffectorState.GraspingState(msg.state[0])
|
|
317
|
+
), EndEffectorState(
|
|
318
|
+
# right claw
|
|
319
|
+
position = [msg.data.position[1]],
|
|
320
|
+
velocity = [msg.data.velocity[1]],
|
|
321
|
+
effort = [msg.data.effort[1]],
|
|
322
|
+
state=EndEffectorState.GraspingState(msg.state[1])
|
|
323
|
+
))
|
|
324
|
+
|
|
325
|
+
def _dexterous_hand_state_callback(self, msg)->None:
|
|
326
|
+
self._eef_state = (EndEffectorState(
|
|
327
|
+
# left hand
|
|
328
|
+
position = list(msg.position[:len(msg.position)//2]),
|
|
329
|
+
velocity = list(msg.velocity[:len(msg.velocity)//2]),
|
|
330
|
+
effort = list(msg.effort[:len(msg.effort)//2]),
|
|
331
|
+
state=EndEffectorState.GraspingState.UNKNOWN
|
|
332
|
+
), EndEffectorState(
|
|
333
|
+
# right hand
|
|
334
|
+
position = list(msg.position[len(msg.position)//2:]),
|
|
335
|
+
velocity = list(msg.velocity[len(msg.velocity)//2:]),
|
|
336
|
+
effort = list(msg.effort[len(msg.effort)//2:]),
|
|
337
|
+
state=EndEffectorState.GraspingState.UNKNOWN
|
|
338
|
+
))
|
|
339
|
+
|
|
340
|
+
def _dexhand_touch_state_callback(self, msg)->None:
|
|
341
|
+
# Update touch state for both hands
|
|
342
|
+
self._dexhand_touch_state = (
|
|
343
|
+
KuavoDexHandTouchState(
|
|
344
|
+
data=tuple(KuavoDexHandTouchState.KuavoTouchState(
|
|
345
|
+
sensor.normal_force1, sensor.normal_force2, sensor.normal_force3,
|
|
346
|
+
sensor.tangential_force1, sensor.tangential_force2, sensor.tangential_force3,
|
|
347
|
+
sensor.tangential_direction1, sensor.tangential_direction2, sensor.tangential_direction3,
|
|
348
|
+
sensor.self_proximity1, sensor.self_proximity2, sensor.mutual_proximity,
|
|
349
|
+
sensor.status
|
|
350
|
+
) for sensor in msg.left_hand)
|
|
351
|
+
), # Left hand touch state
|
|
352
|
+
KuavoDexHandTouchState(
|
|
353
|
+
data=tuple(KuavoDexHandTouchState.KuavoTouchState(
|
|
354
|
+
sensor.normal_force1, sensor.normal_force2, sensor.normal_force3,
|
|
355
|
+
sensor.tangential_force1, sensor.tangential_force2, sensor.tangential_force3,
|
|
356
|
+
sensor.tangential_direction1, sensor.tangential_direction2, sensor.tangential_direction3,
|
|
357
|
+
sensor.self_proximity1, sensor.self_proximity2, sensor.mutual_proximity,
|
|
358
|
+
sensor.status
|
|
359
|
+
) for sensor in msg.right_hand)
|
|
360
|
+
) # Right hand touch state
|
|
361
|
+
)
|
|
362
|
+
|
|
363
|
+
def _humanoid_mpc_gait_changed_callback(self, msg):
|
|
364
|
+
"""
|
|
365
|
+
Callback function for gait change messages.
|
|
366
|
+
Updates the current gait name when a gait change occurs.
|
|
367
|
+
"""
|
|
368
|
+
SDKLogger.debug(f"[State] Received gait change message: {msg.gait_name} at time {msg.start_time}")
|
|
369
|
+
self._gait_manager.add(msg.start_time, msg.gait_name)
|
|
370
|
+
|
|
371
|
+
def _humanoid_mpc_observation_callback(self, msg) -> None:
|
|
372
|
+
"""
|
|
373
|
+
Callback function for MPC observation messages.
|
|
374
|
+
Updates the current MPC state and input data.
|
|
375
|
+
"""
|
|
376
|
+
try:
|
|
377
|
+
self._mpc_observation_data = msg
|
|
378
|
+
# Only update gait info after initialization
|
|
379
|
+
if hasattr(self, '_initialized'):
|
|
380
|
+
curr_time = self._mpc_observation_data.time
|
|
381
|
+
current_gait = self._gait_manager.get_gait(curr_time)
|
|
382
|
+
if self._prev_gait_name != current_gait:
|
|
383
|
+
SDKLogger.debug(f"[State] Gait changed to: {current_gait} at time {curr_time}")
|
|
384
|
+
# Update previous gait name and notify callback if registered
|
|
385
|
+
self._prev_gait_name = current_gait
|
|
386
|
+
if hasattr(self, '_gait_changed_callbacks') and self._gait_changed_callbacks is not None:
|
|
387
|
+
for callback in self._gait_changed_callbacks:
|
|
388
|
+
callback(curr_time, current_gait)
|
|
389
|
+
except Exception as e:
|
|
390
|
+
SDKLogger.error(f"Error processing MPC observation: {e}")
|
|
391
|
+
|
|
392
|
+
def _srv_get_arm_ctrl_mode(self)-> KuavoArmCtrlMode:
|
|
393
|
+
try:
|
|
394
|
+
rospy.wait_for_service('/humanoid_get_arm_ctrl_mode', timeout=1.0)
|
|
395
|
+
get_arm_ctrl_mode_srv = rospy.ServiceProxy('/humanoid_get_arm_ctrl_mode', changeArmCtrlMode)
|
|
396
|
+
req = changeArmCtrlModeRequest()
|
|
397
|
+
resp = get_arm_ctrl_mode_srv(req)
|
|
398
|
+
return KuavoArmCtrlMode(resp.mode)
|
|
399
|
+
except rospy.ServiceException as e:
|
|
400
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
401
|
+
except Exception as e:
|
|
402
|
+
SDKLogger.error(f"[Error] get arm ctrl mode: {e}")
|
|
403
|
+
return None
|
|
404
|
+
|
|
405
|
+
def _srv_get_current_gait_name(self)->str:
|
|
406
|
+
try:
|
|
407
|
+
rospy.wait_for_service('/humanoid_get_current_gait_name', timeout=1.0)
|
|
408
|
+
srv = rospy.ServiceProxy('/humanoid_get_current_gait_name', getCurrentGaitName)
|
|
409
|
+
request = getCurrentGaitNameRequest()
|
|
410
|
+
response = srv(request)
|
|
411
|
+
if response.success:
|
|
412
|
+
return response.gait_name
|
|
413
|
+
else:
|
|
414
|
+
return None
|
|
415
|
+
except Exception as e:
|
|
416
|
+
SDKLogger.error(f"Service call failed: {e}")
|
|
417
|
+
return None
|
|
418
|
+
def _srv_get_dexhand_gesture_state(self)->bool:
|
|
419
|
+
|
|
420
|
+
try:
|
|
421
|
+
rospy.wait_for_service('gesture/execute_state',timeout=1.0)
|
|
422
|
+
# 创建服务代理
|
|
423
|
+
gesture_state_service = rospy.ServiceProxy('gesture/execute_state', gestureExecuteState)
|
|
424
|
+
|
|
425
|
+
# 创建请求对象
|
|
426
|
+
request = gestureExecuteStateRequest()
|
|
427
|
+
|
|
428
|
+
response = gesture_state_service(request)
|
|
429
|
+
|
|
430
|
+
return response.is_executing
|
|
431
|
+
|
|
432
|
+
except rospy.ServiceException as e:
|
|
433
|
+
print(f"Service call failed: {e}")
|
|
434
|
+
|
|
435
|
+
return None
|
|
436
|
+
|
|
437
|
+
def _srv_get_manipulation_mpc_ctrl_mode(self, )->KuavoManipulationMpcCtrlMode:
|
|
438
|
+
try:
|
|
439
|
+
service_name = '/mobile_manipulator_get_mpc_control_mode'
|
|
440
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
441
|
+
get_mode_srv = rospy.ServiceProxy(service_name, changeTorsoCtrlMode)
|
|
442
|
+
|
|
443
|
+
req = changeTorsoCtrlModeRequest()
|
|
444
|
+
|
|
445
|
+
resp = get_mode_srv(req)
|
|
446
|
+
if not resp.result:
|
|
447
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {resp.message}")
|
|
448
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
449
|
+
return KuavoManipulationMpcCtrlMode(resp.mode)
|
|
450
|
+
except rospy.ServiceException as e:
|
|
451
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
452
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
453
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
454
|
+
except Exception as e:
|
|
455
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {e}")
|
|
456
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
457
|
+
|
|
458
|
+
def _srv_get_manipulation_mpc_frame(self, )->KuavoManipulationMpcFrame:
|
|
459
|
+
try:
|
|
460
|
+
service_name = '/get_mm_ctrl_frame'
|
|
461
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
462
|
+
get_frame_srv = rospy.ServiceProxy(service_name, setMmCtrlFrame)
|
|
463
|
+
|
|
464
|
+
req = setMmCtrlFrameRequest()
|
|
465
|
+
|
|
466
|
+
resp = get_frame_srv(req)
|
|
467
|
+
if not resp.result:
|
|
468
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {resp.message}")
|
|
469
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
470
|
+
return KuavoManipulationMpcFrame(resp.currentFrame)
|
|
471
|
+
except rospy.ServiceException as e:
|
|
472
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
473
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
474
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
475
|
+
except Exception as e:
|
|
476
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {e}")
|
|
477
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
478
|
+
|
|
479
|
+
def _srv_get_manipulation_mpc_control_flow(self, )->KuavoManipulationMpcControlFlow:
|
|
480
|
+
try:
|
|
481
|
+
service_name = '/get_mm_wbc_arm_trajectory_control'
|
|
482
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
483
|
+
get_mode_srv = rospy.ServiceProxy(service_name, changeArmCtrlMode)
|
|
484
|
+
|
|
485
|
+
req = changeArmCtrlModeRequest()
|
|
486
|
+
|
|
487
|
+
resp = get_mode_srv(req)
|
|
488
|
+
if not resp.result:
|
|
489
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {resp.message}")
|
|
490
|
+
return KuavoManipulationMpcControlFlow.Error
|
|
491
|
+
return KuavoManipulationMpcControlFlow(resp.mode)
|
|
492
|
+
except rospy.ServiceException as e:
|
|
493
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
494
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
495
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
496
|
+
except Exception as e:
|
|
497
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {e}")
|
|
498
|
+
return KuavoManipulationMpcControlFlow.Error
|
|
499
|
+
|
|
500
|
+
def _srv_get_manipulation_mpc_ctrl_mode(self, )->KuavoManipulationMpcCtrlMode:
|
|
501
|
+
try:
|
|
502
|
+
service_name = '/mobile_manipulator_get_mpc_control_mode'
|
|
503
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
504
|
+
get_mode_srv = rospy.ServiceProxy(service_name, changeTorsoCtrlMode)
|
|
505
|
+
|
|
506
|
+
req = changeTorsoCtrlModeRequest()
|
|
507
|
+
|
|
508
|
+
resp = get_mode_srv(req)
|
|
509
|
+
if not resp.result:
|
|
510
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {resp.message}")
|
|
511
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
512
|
+
return KuavoManipulationMpcCtrlMode(resp.mode)
|
|
513
|
+
except rospy.ServiceException as e:
|
|
514
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
515
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
516
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
517
|
+
except Exception as e:
|
|
518
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {e}")
|
|
519
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
520
|
+
|
|
521
|
+
def _srv_get_manipulation_mpc_frame(self, )->KuavoManipulationMpcFrame:
|
|
522
|
+
try:
|
|
523
|
+
service_name = '/get_mm_ctrl_frame'
|
|
524
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
525
|
+
get_frame_srv = rospy.ServiceProxy(service_name, setMmCtrlFrame)
|
|
526
|
+
|
|
527
|
+
req = setMmCtrlFrameRequest()
|
|
528
|
+
|
|
529
|
+
resp = get_frame_srv(req)
|
|
530
|
+
if not resp.result:
|
|
531
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {resp.message}")
|
|
532
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
533
|
+
return KuavoManipulationMpcFrame(resp.currentFrame)
|
|
534
|
+
except rospy.ServiceException as e:
|
|
535
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
536
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
537
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
538
|
+
except Exception as e:
|
|
539
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {e}")
|
|
540
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
541
|
+
|
|
542
|
+
def _srv_get_manipulation_mpc_control_flow(self, )->KuavoManipulationMpcControlFlow:
|
|
543
|
+
try:
|
|
544
|
+
service_name = '/get_mm_wbc_arm_trajectory_control'
|
|
545
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
546
|
+
get_mode_srv = rospy.ServiceProxy(service_name, changeArmCtrlMode)
|
|
547
|
+
|
|
548
|
+
req = changeArmCtrlModeRequest()
|
|
549
|
+
|
|
550
|
+
resp = get_mode_srv(req)
|
|
551
|
+
if not resp.result:
|
|
552
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {resp.message}")
|
|
553
|
+
return KuavoManipulationMpcControlFlow.Error
|
|
554
|
+
return KuavoManipulationMpcControlFlow(resp.mode)
|
|
555
|
+
except rospy.ServiceException as e:
|
|
556
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
557
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
558
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
559
|
+
except Exception as e:
|
|
560
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {e}")
|
|
561
|
+
return KuavoManipulationMpcControlFlow.Error
|
|
562
|
+
|
|
563
|
+
def _srv_get_manipulation_mpc_ctrl_mode(self, )->KuavoManipulationMpcCtrlMode:
|
|
564
|
+
try:
|
|
565
|
+
service_name = '/mobile_manipulator_get_mpc_control_mode'
|
|
566
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
567
|
+
get_mode_srv = rospy.ServiceProxy(service_name, changeTorsoCtrlMode)
|
|
568
|
+
|
|
569
|
+
req = changeTorsoCtrlModeRequest()
|
|
570
|
+
|
|
571
|
+
resp = get_mode_srv(req)
|
|
572
|
+
if not resp.result:
|
|
573
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {resp.message}")
|
|
574
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
575
|
+
return KuavoManipulationMpcCtrlMode(resp.mode)
|
|
576
|
+
except rospy.ServiceException as e:
|
|
577
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
578
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
579
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
580
|
+
except Exception as e:
|
|
581
|
+
SDKLogger.error(f"Failed to get manipulation mpc control mode: {e}")
|
|
582
|
+
return KuavoManipulationMpcCtrlMode.ERROR
|
|
583
|
+
|
|
584
|
+
def _srv_get_manipulation_mpc_frame(self, )->KuavoManipulationMpcFrame:
|
|
585
|
+
try:
|
|
586
|
+
service_name = '/get_mm_ctrl_frame'
|
|
587
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
588
|
+
get_frame_srv = rospy.ServiceProxy(service_name, setMmCtrlFrame)
|
|
589
|
+
|
|
590
|
+
req = setMmCtrlFrameRequest()
|
|
591
|
+
|
|
592
|
+
resp = get_frame_srv(req)
|
|
593
|
+
if not resp.result:
|
|
594
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {resp.message}")
|
|
595
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
596
|
+
return KuavoManipulationMpcFrame(resp.currentFrame)
|
|
597
|
+
except rospy.ServiceException as e:
|
|
598
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
599
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
600
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
601
|
+
except Exception as e:
|
|
602
|
+
SDKLogger.error(f"Failed to get manipulation mpc frame: {e}")
|
|
603
|
+
return KuavoManipulationMpcFrame.ERROR
|
|
604
|
+
|
|
605
|
+
def _srv_get_manipulation_mpc_control_flow(self, )->KuavoManipulationMpcControlFlow:
|
|
606
|
+
try:
|
|
607
|
+
service_name = '/get_mm_wbc_arm_trajectory_control'
|
|
608
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
609
|
+
get_mode_srv = rospy.ServiceProxy(service_name, changeArmCtrlMode)
|
|
610
|
+
|
|
611
|
+
req = changeArmCtrlModeRequest()
|
|
612
|
+
|
|
613
|
+
resp = get_mode_srv(req)
|
|
614
|
+
if not resp.result:
|
|
615
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {resp.message}")
|
|
616
|
+
return KuavoManipulationMpcControlFlow.Error
|
|
617
|
+
return KuavoManipulationMpcControlFlow(resp.mode)
|
|
618
|
+
except rospy.ServiceException as e:
|
|
619
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
620
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
621
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
622
|
+
except Exception as e:
|
|
623
|
+
SDKLogger.error(f"Failed to get manipulation mpc wbc arm trajectory control mode: {e}")
|
|
624
|
+
return KuavoManipulationMpcControlFlow.Error
|
|
625
|
+
|
|
626
|
+
def _srv_get_pitch_limit_status(self, )->Tuple[bool, str]:
|
|
627
|
+
try:
|
|
628
|
+
service_name = '/humanoid/mpc/pitch_limit_status'
|
|
629
|
+
rospy.wait_for_service(service_name, timeout=2.0)
|
|
630
|
+
get_pitch_limit_status_srv = rospy.ServiceProxy(service_name, SetBool)
|
|
631
|
+
|
|
632
|
+
req = SetBoolRequest()
|
|
633
|
+
|
|
634
|
+
resp = get_pitch_limit_status_srv(req)
|
|
635
|
+
if not resp.success:
|
|
636
|
+
SDKLogger.error(f"Failed to get pitch limit status: {resp.message}")
|
|
637
|
+
return False, 'unknown'
|
|
638
|
+
return resp.success, resp.message
|
|
639
|
+
except rospy.ServiceException as e:
|
|
640
|
+
SDKLogger.error(f"Service call to {service_name} failed: {e}")
|
|
641
|
+
except rospy.ROSException as e: # For timeout from wait_for_service
|
|
642
|
+
SDKLogger.error(f"Failed to connect to service {service_name}: {e}")
|
|
643
|
+
except Exception as e:
|
|
644
|
+
SDKLogger.error(f"Failed to get pitch limit status: {e}")
|
|
645
|
+
return False, 'unknown'
|
|
646
|
+
|
|
647
|
+
if __name__ == "__main__":
|
|
648
|
+
state = KuavoRobotStateCore()
|
|
649
|
+
print(state.manipulation_mpc_frame)
|
|
650
|
+
print(state.manipulation_mpc_control_flow)
|
|
651
|
+
print(state.manipulation_mpc_ctrl_mode)
|
|
652
|
+
print(state.arm_control_mode)
|