机器人信息获取接口
KUAVO Humanoid SDK 提供了全面的机器人信息获取接口,支持获取机器人的基本信息、状态信息、IMU数据等。本文档详细介绍这些接口的使用方法。
说明
在使用这些接口之前,请确保已完成 KUAVO Humanoid SDK 的安装配置,详细安装步骤请参考《安装指南》。
接口说明
KuavoRobotInfo
KuavoRobotInfo
类提供了获取机器人基本信息的接口。
属性接口
属性名 | robot_version |
---|---|
类型 | str |
功能概述 | 获取机器人版本号。 |
返回值 | 机器人版本号,例如:"42"、"43" 等 |
备注 | 只读属性 |
属性名 | end_effector_type |
---|---|
类型 | str |
功能概述 | 获取末端执行器类型。 |
返回值 | 末端执行器类型,"qiangnao" 表示灵巧手,"lejuclaw" 表示乐聚夹爪 |
备注 | 只读属性 |
属性名 | joint_dof |
---|---|
类型 | int |
功能概述 | 获取机器人总关节数。 |
返回值 | 机器人总关节数 |
备注 | 只读属性 |
属性名 | joint_names |
---|---|
类型 | list |
功能概述 | 获取机器人所有关节名称列表。 |
返回值 | 包含所有关节名称的列表 |
备注 | 只读属性 |
属性名 | arm_joint_dof |
---|---|
类型 | int |
功能概述 | 获取机器人手臂自由度数量。 |
返回值 | 手臂关节数量,例如:14 |
备注 | 只读属性 |
属性名 | arm_joint_names |
---|---|
类型 | list |
功能概述 | 获取机器人手臂关节名称列表。 |
返回值 | 包含手臂关节名称的列表 |
备注 | 只读属性 |
属性名 | head_joint_dof |
---|---|
类型 | int |
功能概述 | 获取机器人头部自由度数量。 |
返回值 | 头部关节数量 |
备注 | 只读属性 |
属性名 | head_joint_names |
---|---|
类型 | list |
功能概述 | 获取机器人头部关节名称列表。 |
返回值 | 包含头部关节名称的列表 |
备注 | 只读属性 |
属性名 | eef_frame_names |
---|---|
类型 | Tuple[str, str] |
功能概述 | 获取末端执行器坐标系名称。 |
返回值 | 包含左右手坐标系名称的元组,例如:("zarm_l7_link", "zarm_r7_link") |
备注 | 只读属性 |
KuavoRobotState
KuavoRobotState
类提供了获取机器人实时状态的接口。
方法接口
函数名 | is_stance |
---|---|
函数原型 | bool is_stance() |
功能概述 | 判断机器人是否处于准备姿态。 |
参数 | 无 |
返回值 | True: 处于准备姿态 False: 不处于准备姿态 |
备注 | 无 |
函数名 | is_walk |
---|---|
函数原型 | bool is_walk() |
功能概述 | 判断机器人是否处于行走状态。 |
参数 | 无 |
返回值 | True: 处于行走状态 False: 不处于行走状态 |
备注 | 无 |
函数名 | is_step_control |
---|---|
函数原型 | bool is_step_control() |
功能概述 | 判断机器人是否处于单步控制状态。 |
参数 | 无 |
返回值 | True: 处于单步控制状态 False: 不处于单步控制状态 |
备注 | 无 |
函数名 | arm_control_mode |
---|---|
函数原型 | KuavoArmCtrlMode arm_control_mode() |
功能概述 | 获取手臂控制模式。 |
参数 | 无 |
返回值 | KuavoArmCtrlMode 枚举值: - ArmFixed(0): 固定模式 - AutoSwing(1): 自动摆动模式 - ExternalControl(2): 外部控制模式 |
备注 | 无 |
函数名 | arm_joint_state |
---|---|
函数原型 | KuavoJointData arm_joint_state() |
功能概述 | 获取机器人手臂关节状态数据。 |
参数 | 无 |
返回值 | KuavoJointData 类型,包含: - position: 关节角度(弧度) - velocity: 关节速度(弧度/秒) - torque: 关节力矩(牛米或安培) - acceleration: 关节加速度(弧度/秒²) |
备注 | 返回数据为实时数据 |
函数名 | head_joint_state |
---|---|
函数原型 | KuavoJointData head_joint_state() |
功能概述 | 获取机器人头部关节状态数据。 |
参数 | 无 |
返回值 | KuavoJointData 类型,包含: - position: 关节角度(弧度) - velocity: 关节速度(弧度/秒) - torque: 关节力矩(牛米或安培) - acceleration: 关节加速度(弧度/秒²) |
备注 | 返回数据为实时数据 |
函数名 | robot_position |
---|---|
函数原型 | Tuple[float, float, float] robot_position() |
功能概述 | 获取机器人在世界坐标系中的位置。 |
参数 | 无 |
返回值 | 包含(x, y, z)坐标的元组,单位:米 |
备注 | 返回数据为实时数据 |
函数名 | robot_orientation |
---|---|
函数原型 | Tuple[float, float, float, float] robot_orientation() |
功能概述 | 获取机器人在世界坐标系中的姿态。 |
参数 | 无 |
返回值 | 包含(x, y, z, w)四元数的元组 |
备注 | 返回数据为实时数据 |
函数名 | linear_velocity |
---|---|
函数原型 | Tuple[float, float, float] linear_velocity() |
功能概述 | 获取机器人在世界坐标系中的线速度。 |
参数 | 无 |
返回值 | 包含(x, y, z)线速度的元组,单位:米/秒 |
备注 | 返回数据为实时数据 |
函数名 | angular_velocity |
---|---|
函数原型 | Tuple[float, float, float] angular_velocity() |
功能概述 | 获取机器人在世界坐标系中的角速度。 |
参数 | 无 |
返回值 | 包含(x, y, z)角速度的元组,单位:弧度/秒 |
备注 | 返回数据为实时数据 |
函数名 | wait_for_stance |
---|---|
函数原型 | bool wait_for_stance(timeout=5.0) |
功能概述 | 等待机器人进入准备姿态。 |
参数 | timeout: 超时时间,单位:秒,默认值:5.0 |
返回值 | True: 成功进入准备姿态 False: 超时未进入准备姿态 |
备注 | 阻塞函数,会等待直到状态变化或超时 |
函数名 | wait_for_walk |
---|---|
函数原型 | bool wait_for_walk(timeout=5.0) |
功能概述 | 等待机器人进入行走状态。 |
参数 | timeout: 超时时间,单位:秒,默认值:5.0 |
返回值 | True: 成功进入行走状态 False: 超时未进入行走状态 |
备注 | 阻塞函数,会等待直到状态变化或超时 |
函数名 | wait_for_step_control |
---|---|
函数原型 | bool wait_for_step_control(timeout=5.0) |
功能概述 | 等待机器人进入单步控制状态。 |
参数 | timeout: 超时时间,单位:秒,默认值:5.0 |
返回值 | True: 成功进入单步控制状态 False: 超时未进入单步控制状态 |
备注 | 阻塞函数,会等待直到状态变化或超时 |
函数名 | wait_for_trot |
---|---|
函数原型 | bool wait_for_trot(timeout=5.0) |
功能概述 | 等待机器人进入小跑状态。 |
参数 | timeout: 超时时间,单位:秒,默认值:5.0 |
返回值 | True: 成功进入小跑状态 False: 超时未进入小跑状态 |
备注 | 阻塞函数,会等待直到状态变化或超时 |
属性接口
属性名 | imu_data |
---|---|
类型 | KuavoImuData |
功能概述 | 获取IMU数据。 |
返回值 | KuavoImuData 类型,包含陀螺仪、加速度计和姿态信息 |
备注 | 只读属性 |
属性名 | odometry |
---|---|
类型 | KuavoOdometry |
功能概述 | 获取里程计数据。 |
返回值 | KuavoOdometry 类型,包含位置、姿态、线速度和角速度信息 |
备注 | 只读属性 |
属性名 | com_height |
---|---|
类型 | float |
功能概述 | 获取机器人质心高度。 |
返回值 | 质心高度,单位:米 |
备注 | 只读属性 |
数据类型
KuavoJointData
关节数据结构体,包含以下字段:
class KuavoJointData:
position: list # 关节位置(角度),单位:弧度
velocity: list # 关节速度,单位:弧度/秒
torque: list # 关节力矩,单位:牛米或安培
acceleration: list # 关节加速度,单位:弧度/秒²
KuavoImuData
IMU数据结构体,包含以下字段:
class KuavoImuData:
gyro: Tuple[float, float, float] # 角速度(x, y, z),单位:弧度/秒
acc: Tuple[float, float, float] # 线加速度(x, y, z),单位:米/秒²
free_acc: Tuple[float, float, float] # 去重力加速度(x, y, z),单位:米/秒²
quat: Tuple[float, float, float, float] # 方向四元数(x, y, z, w)
KuavoOdometry
里程计数据结构体,包含以下字段:
class KuavoOdometry:
position: Tuple[float, float, float] # 位置(x, y, z),单位:米
orientation: Tuple[float, float, float, float] # 姿态四元数(x, y, z, w)
linear: Tuple[float, float, float] # 线速度(x, y, z),单位:米/秒
angular: Tuple[float, float, float] # 角速度(x, y, z),单位:弧度/秒
KuavoArmCtrlMode
手臂控制模式枚举:
class KuavoArmCtrlMode(Enum):
ArmFixed = 0 # 固定模式
AutoSwing = 1 # 自动摆动模式
ExternalControl = 2 # 外部控制模式
示例代码
from kuavo_humanoid_sdk import KuavoSDK, KuavoRobotInfo
def main():
# 初始化SDK
if not KuavoSDK().Init():
print("SDK初始化失败!")
exit(1)
# 创建机器人信息实例
robot_info = KuavoRobotInfo()
# 获取基本信息
print(f"机器人版本: {robot_info.robot_version}")
print(f"末端执行器类型: {robot_info.end_effector_type}")
print(f"机器人总关节数: {robot_info.joint_dof}")
print(f"手臂自由度: {robot_info.arm_joint_dof}")
print(f"头部自由度: {robot_info.head_joint_dof}")
# 获取关节名称
print(f"关节名称列表: {robot_info.joint_names}")
print(f"手臂关节名称: {robot_info.arm_joint_names}")
print(f"头部关节名称: {robot_info.head_joint_names}")
# 获取末端执行器坐标系名称
left_frame, right_frame = robot_info.eef_frame_names
print(f"左手坐标系: {left_frame}")
print(f"右手坐标系: {right_frame}")
if __name__ == "__main__":
main()
详细示例请参考SDK示例代码:<kuavo-ros-opensource>/src/kuavo_humanoid_sdk/examples/robot_info_example.py