运动控制接口
介绍
运动控制接口:通过调用 Python 函数,控制机器人的站立/躺下、姿态、步态、充电及速度等运动行为。
| 功能 | Python |
|---|---|
| 站立 | ✔ |
| 躺下 | ✔ |
| 获取机器人姿态状态 | ✔ |
| 调整站立高度 | ✔ |
| 设置步态 | ✔ |
| 获取步态 | ✔ |
| 设置控制模式 | ✔ |
| 获取控制模式 | ✔ |
| 前往充电座 | ✔ |
| 离开充电座 | ✔ |
| 获取充电座状态 | ✔ |
| 获取电池状态 | ✔ |
| 检查充电状态 | ✔ |
| 速度控制 | ✔ |
站立与躺下
Python接口
stand_up(timeout=30)
功能说明
使机器人站立。该函数会智能检查当前姿态状态后再发送指令:
- 已处于站立状态:立即返回成功,不发送额外指令
- 正在站立过程中:返回失败(需等待完成)
- 处于躺下状态:发送站立指令
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
timeout | int | 默认: 30 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
StandUpResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import stand_up
result = stand_up()
if result.response.result:
print("机器人已站立")
else:
print(f"站立失败: {result.state.describe}")lie_down(timeout=30)
功能说明
使机器人躺下。该函数会智能检查当前姿态状态后再发送指令:
- 已处于躺下状态:立即返回成功,不发送额外指令
- 正在站立过程中:返回失败(不能中断)
- 处于站立状态:发送躺下指令
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
timeout | int | 默认: 30 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
LieDownResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import lie_down
result = lie_down()
if result.response.result:
print("机器人已躺下")
else:
print(f"躺下失败: {result.state.describe}")get_robot_state()
功能说明
获取机器人当前的姿态状态,自动进行数据有效性验证。数据过期或不可用时返回 UNKNOWN_STATE。
参数说明
无参数。
返回值
| 类型 | 说明 |
|---|---|
GetRobotStateResponse | state.code == 0 表示成功;robot_state 为 RobotState 枚举:LIE_DOWN(0) 躺下、STANDING_UP(1) 站立中、STAND_UP(2) 已站立、UNKNOWN_STATE(99) 未知。 |
调用示例
from daystar_api.lowlevel_skills import get_robot_state, RobotState
response = get_robot_state()
if response.state.code == 0:
if response.robot_state == RobotState.STAND_UP:
print("机器人正在站立")
elif response.robot_state == RobotState.LIE_DOWN:
print("机器人正在躺下")身体控制
Python接口
adjust_body_height(percent, timeout=5)
功能说明
调整机器人站立高度(百分比)。机器人必须处于站立状态才能调整高度,有效范围为 20–50。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
percent | int | 必填 | 高度百分比,有效范围 20–50。 |
timeout | int | 默认: 5 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
RobotCommandResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import adjust_body_height
result = adjust_body_height(30)
if result.response.result:
print("高度已调整为 30%")set_gait(gait_type, timeout=5)
功能说明
设置机器人步态类型。机器人必须处于站立状态才能切换步态。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
gait_type | GaitType | 必填 | 步态类型枚举。GaitType.TROT(0) 普通步态;GaitType.NORMAL_STAIR(1) 普通楼梯步态;GaitType.SENSE_STAIR(6) 感知楼梯步态;GaitType.POSE_ADJUST(13) 姿态调整;GaitType.CAR_MODE(14) 爬行模式;GaitType.RL_TROT(0x20) RL 步态;GaitType.RL_MOUNTAIN(0x21) RL 山地步态。 |
timeout | int | 默认: 5 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
RobotCommandResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import set_gait, GaitType
result = set_gait(GaitType.TROT)
if result.response.result:
print("步态已设置为普通步态")get_gait()
功能说明
获取机器人当前步态类型,自动进行数据有效性验证。数据过期或不可用时返回 UNKNOWN_GAIT。
参数说明
无参数。
返回值
| 类型 | 说明 |
|---|---|
GetGaitResponse | state.code == 0 表示成功;gait_type 为 GaitType 枚举值。 |
调用示例
from daystar_api.lowlevel_skills import get_gait, GaitType
response = get_gait()
if response.state.code == 0:
print(f"当前步态: {response.gait_type}")控制模式
Python接口
set_control_mode(mode, timeout=5)
功能说明
设置机器人控制模式,在手动模式和自动导航模式之间切换。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
mode | ControlMode | 必填 | 控制模式枚举。ControlMode.JOY_MODE(0) 手柄手动控制;ControlMode.NAV_MODE(1) 导航自动控制。 |
timeout | int | 默认: 5 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
RobotCommandResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import set_control_mode, ControlMode
# 切换到导航模式
result = set_control_mode(ControlMode.NAV_MODE)
if result.response.result:
print("已切换至导航模式")get_control_mode()
功能说明
获取机器人当前控制模式,自动进行数据有效性验证。数据过期或不可用时返回 UNKNOWN_MODE。
参数说明
无参数。
返回值
| 类型 | 说明 |
|---|---|
GetControlModeResponse | state.code == 0 表示成功;control_mode 为 ControlMode 枚举:JOY_MODE(0) 手柄模式、NAV_MODE(1) 导航模式、UNKNOWN_MODE(99) 未知。 |
调用示例
from daystar_api.lowlevel_skills import get_control_mode, ControlMode
response = get_control_mode()
if response.state.code == 0:
if response.control_mode == ControlMode.NAV_MODE:
print("当前为导航模式")充电功能
Python接口
go_to_dock(timeout=60)
功能说明
控制机器人前往充电座。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
timeout | int | 默认: 60 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
GoToDockResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import go_to_dock
result = go_to_dock()
if result.response.result:
print("机器人正在前往充电座")leave_dock(timeout=60)
功能说明
控制机器人离开充电座。机器人必须处于充电座上才能执行此指令。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
timeout | int | 默认: 60 | 服务调用超时时间(秒)。 |
返回值
| 类型 | 说明 |
|---|---|
LeaveDockResponse | state.code == 0 表示成功;response.result 为布尔值,表示指令是否执行成功。 |
调用示例
from daystar_api.lowlevel_skills import leave_dock
result = leave_dock()
if result.response.result:
print("机器人正在离开充电座")get_dock_state()
功能说明
获取充电座当前状态,自动进行数据有效性验证。数据过期或不可用时返回 UNKNOWN_DOCK。
参数说明
无参数。
返回值
| 类型 | 说明 |
|---|---|
GetDockStateResponse | state.code == 0 表示成功;dock_state 为 DockState 枚举:IDLE(0) 空闲、GOING_TO_DOCK(1) 前往充电座、LIE_ON_DOCKER(4) 充电中、LEAVE_DOCK(7) 已离开、UNKNOWN_DOCK(99) 未知。 |
调用示例
from daystar_api.lowlevel_skills import get_dock_state, DockState
response = get_dock_state()
if response.state.code == 0:
if response.dock_state == DockState.LIE_ON_DOCKER:
print("机器人正在充电座上充电")电池状态
Python接口
get_battery_state()
功能说明
获取机器人完整的电池状态信息,自动进行数据有效性验证。数据过期或不可用时 is_valid 为 False。
参数说明
无参数。
返回值
| 类型 | 说明 |
|---|---|
GetBatteryStateResponse | state.code == 0 表示成功;is_valid 表示数据是否有效;battery_state.percentage 电量百分比(0–100);battery_state.voltage 电压(V);battery_state.current 电流(A,负值表示放电);battery_state.temperature 温度(°C);battery_state.power_supply_status 充电状态(1=充电中,4=已满)。 |
调用示例
from daystar_api.lowlevel_skills import get_battery_state
response = get_battery_state()
if response.state.code == 0 and response.is_valid:
battery = response.battery_state
print(f"电量: {battery.percentage}%")
print(f"电压: {battery.voltage}V")
print(f"温度: {battery.temperature}°C")is_charge()
功能说明
检查机器人当前是否正在充电,自动进行数据有效性验证。数据过期或不可用时返回 False。
参数说明
无参数。
返回值
| 类型 | 说明 |
|---|---|
IsChargeResponse | state.code == 0 表示成功;is_charging 为布尔值,True 表示正在充电,False 表示未充电(或数据不可用)。 |
调用示例
from daystar_api.lowlevel_skills import is_charge
response = is_charge()
if response.is_charging:
print("机器人正在充电")
else:
print("机器人未充电")速度控制
Python接口
send_cmd_vel(linear_x=0.0, linear_y=0.0, angular_z=0.0, dt=1.0, blocking=True)
功能说明
通过 /cmd_vel 话题发送速度指令,控制机器人运动方向和速度,支持全向移动。支持阻塞和非阻塞两种模式。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
linear_x | float | 默认: 0.0 | 前进/后退线速度(m/s)。正值前进,负值后退。普通步态平地推荐范围 [-1.0, 2.0]。 |
linear_y | float | 默认: 0.0 | 左右横移线速度(m/s,全向移动)。正值左移,负值右移。普通步态推荐范围 [-0.4, 0.4]。 |
angular_z | float | 默认: 0.0 | 角速度(rad/s)。正值逆时针(左转),负值顺时针(右转)。普通步态推荐范围 [-0.8, 0.8]。 |
dt | float | 默认: 1.0 | 运动持续时间(秒)。dt > 0 时自动在 dt 秒后停止;dt = 0 时持续运动直到手动发送停止指令。 |
blocking | bool | 默认: True | True 时阻塞等待运动完成;False 时立即返回,运动在后台执行。 |
返回值
| 类型 | 说明 |
|---|---|
SendCmdVelResponse | state.code == 0 表示成功;success 字段表示指令是否发送成功。 |
调用示例
from daystar_api.lowlevel_skills import send_cmd_vel
# 前进 1 秒(阻塞)
result = send_cmd_vel(linear_x=0.5, dt=1.0)
# 原地左转(非阻塞,后台执行)
result = send_cmd_vel(angular_z=0.3, dt=2.0, blocking=False)
# 持续前进(需手动停止)
send_cmd_vel(linear_x=0.3, dt=0.0)
# ... 执行其他操作 ...
send_cmd_vel() # 发送停止指令