运动状态服务接口
| 接口名称 | 功能概述 | C++ | Python | C# | ROS |
| 获取运动状态信息 | 错误信息 | ✔ | ✔ | ✔ | |
| 通信状态 | ✔ | ✔ | ✔ | ✔ | |
| 当前场景 | ✔ | ✔ | ✔ | ✔ | |
| 场景切换状态 | ✔ | ✔ | ✔ | ||
| 驱动器状态 | ✔ | ✔ | ✔ | ||
| 控制模式 | ✔ | ✔ | ✔ | ✔ | |
| 避障状态 | ✔ | ✔ | ✔ | ||
| 当前速度 | ✔ | ✔ | ✔ | ||
| 当前高度 | ✔ | ✔ | ✔ | ||
| 当前姿态 | ✔ | ✔ | ✔ | ✔ | |
| UWB状态 | ✔ | ✔ | ✔ | ||
| 急停状态 | ✔ | ✔ | ✔ |
C++接口
获取运动状态信息
void setStatusCallback(MCSStatusCallback callback)
功能说明
设置MCS状态回调(合并回调接口)。该回调函数会在MCS系统状态发生变化时被调用,包含机器人的完整状态信息。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
callback | MCSStatusCallback | 必填 | MCS状态回调函数。接收包含所有MCS系统状态的完整状态结构体。 |
回调类型说明
cpp
/**
* @brief MCS系统状态信息结构体,包含所有MCS相关状态
*/
struct MCSStatusInfo
{
std::string errorMessage; ///< 错误信息
int64_t heartBeat; ///< 心跳值
SceneType scene; ///< 当前场景
SceneSwitchStateType switchState; ///< 场景切换状态
DriverEnableState driverState; ///< 使能状态
ControllerMode controllerMode; ///< 控制模式
bool guardianSwitchActive; ///< 停障开关状态
GuardianVelocityDecayRatio guardianVelocityDecayRatio; ///< 各个方向障碍物检测
MCSMotionInfo motion; ///< 运动参数
/**
* @brief 默认构造函数
*/
MCSStatusInfo()
: errorMessage(""),
heartBeat(0),
scene(SceneType::NULL_SCENE),
switchState(SceneSwitchStateType::NULL_SCENE),
driverState(DriverEnableState::DISABLED),
controllerMode(ControllerMode::NALL_CONTROL),
guardianSwitchActive(false),
guardianVelocityDecayRatio({0.0f, 0.0f, 0.0f, 0.0f}),
motion() {}
};MCSStatusInfo 结构体说明
| 字段名称 | 类型 | 描述 |
|---|---|---|
errorMessage | std::string | 系统错误描述。 |
heartBeat | int64_t | 心跳计数,用于检测通信状态。 |
scene | SceneType | 当前运动场景模式。 |
switchState | SceneSwitchStateType | 场景切换进度。 |
driverState | DriverEnableState | 驱动器使能状态。 |
controllerMode | ControllerMode | 当前控制模式(导航/手柄)。 |
guardianSwitchActive | bool | 安全停障功能状态(True: 激活, False: 关闭)。 |
guardianVelocityDecayRatio | GuardianVelocityDecayRatio | 各方向的速度衰减系数(障碍物检测)。 |
motion | MCSMotionInfo | 当前速度和高度信息。 |
SceneSwitchStateType 枚举
| 值 | 描述 |
|---|---|
NULL_SCENE | 未知状态 (0)。 |
SWITCHING | 切换中状态 (1)。 |
SUCCEEDED | 切换成功 (2)。 |
FAILED | 错误状态 (3)。 |
DriverEnableState 枚举
| 值 | 描述 |
|---|---|
UNKNOWN | 未知状态 (0)。 |
ENABLED | 已使能 (1)。 |
ENABLING | 正在使能中 (2)。 |
ENABLE_FILED | 使能失败 (3)。 |
DISABLED | 非使能状态 (4)。 |
GuardianVelocityDecayRatio 结构体
| 字段名称 | 类型 | 描述 |
|---|---|---|
left_ratio | float | 左方向障碍物检测状态(< 0: 有障碍物, ≥ 0: 无障碍物)。 |
front_ratio | float | 前方向障碍物检测状态(< 0: 有障碍物, ≥ 0: 无障碍物)。 |
right_ratio | float | 右方向障碍物检测状态(< 0: 有障碍物, ≥ 0: 无障碍物)。 |
rear_ratio | float | 后方向障碍物检测状态(< 0: 有障碍物, ≥ 0: 无障碍物)。 |
返回值
| 类型 | 说明 |
|---|---|
void | 无。 |
调用示例
cpp
// MCS系统状态回调函数
void onMCSStatusChanged(const MCSStatusInfo &status)
{
std::cout << "\n===== MCS 系统状态更新 =====" << std::endl;
std::cout << "错误信息: " << (status.errorMessage.empty() ? "无" : status.errorMessage) << std::endl;
std::cout << "心跳值: " << status.heartBeat << std::endl;
std::cout << "当前场景: " << sceneTypeToString(status.scene) << std::endl;
std::cout << "使能状态: " << driverEnableStateToString(status.driverState) << std::endl;
std::cout << "停障开关: " << (status.guardianSwitchActive ? "激活" : "关闭") << std::endl;
std::cout << "运动速度: " << (status.motion.speed * 100) << "%" << std::endl;
std::cout << "机身高度: " << (status.motion.height * 100) << "%" << std::endl;
std::cout << "=============================" << std::endl;
}
Lenovo::Daystar::SDK sdk;
if (!sdk.isConnected()) {
std::cerr << "Can not connect SDK server with default settings"
<< std::endl;
return 1;
} else {
std::cout << "Connected with default settings" << std::endl;
}
auto &sport = sdk.getSport();
sport.setStatusCallback(onMCSStatusChanged);注意事项
com_state必须指向有效的common::ROBOT_COMMON_STATUS结构体。
void setMotionCallback(MCSMotionCallback callback)
功能说明
设置MCS运动参数回调(合并回调接口)。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
callback | MCSMotionCallback | 必填 | MCS运动参数回调函数。接收包含速度和高度的运动参数结构体。 |
回调类型说明
cpp
/**
* @brief MCS运动状态信息结构体,包含运动相关参数
*/
struct MCSMotionInfo
{
float speed; ///< 当前速度百分比 (0.0-1.0)
float height; ///< 当前高度百分比 (0.0-1.0)
/**
* @brief 默认构造函数
*/
MCSMotionInfo() : speed(0.0f), height(0.0f) {}
/**
* @brief 带参数构造函数
*/
MCSMotionInfo(float spd, float hgt) : speed(spd), height(hgt) {}
};MCSMotionInfo 结构体说明
| 字段名称 | 类型 | 描述 |
|---|---|---|
speed | float | 当前速度百分比 (0.0-1.0)。 |
height | float | 当前高度百分比 (0.0-1.0)。 |
返回值
| 类型 | 说明 |
|---|---|
void | 无。 |
调用示例
cpp
// MCS运动参数回调函数
void onMCSMotionChanged(const MCSMotionInfo &motion)
{
std::cout << "\n--- 运动参数更新 ---" << std::endl;
std::cout << "速度: " << (motion.speed * 100) << "%" << std::endl;
std::cout << "高度: " << (motion.height * 100) << "%" << std::endl;
std::cout << "------------------" << std::endl;
}
if (!sdk.isConnected()) {
std::cerr << "Can not connect SDK server with default settings"
<< std::endl;
return 1;
} else {
std::cout << "Connected with default settings" << std::endl;
}
auto &sport = sdk.getSport();
sport.setMotionCallback(onMCSMotionChanged);Python接口
获取运动状态信息
tuple get_common_status()
功能说明
获取机器人通用状态信息。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
| 无 | - | - | 无参数 |
返回值
| 类型 | 说明 |
|---|---|
tuple | 返回 (success, common_status)。success为布尔值,common_status为包含状态字段的对象。 |
common_status 对象说明
| 字段名称 | 类型 | 描述 |
|---|---|---|
network | int | 机器人当前网络状态 (0-100)。 |
belie_or_stand | int | 当前姿态 (0:未知, 1:趴下, 2:切换中, 3:站立)。 |
emergency | bool | 是否处于急停状态。 |
avoidance | bool | 自动避障状态。 |
heartbeat | int64 | 心跳计数。 |
cur_speed | float | 当前速度。 |
cur_height | float | 当前高度。 |
max_speed | float | 最大速度。 |
max_height | float | 最大高度。 |
cur_scene_switch_state | int | 场景切换状态 (0:无, 1:切换中, 2:成功, 3:失败)。 |
cur_scene | int | 当前场景 (0:无, 2:行走步态, 3:楼梯步态, 9:RL步态, 10:斜坡步态, ...)。 |
driver_enable_state | int | 驱动器使能状态 (0:未知, 1:已使能, 2:使能中, 3:失败, 4:未使能)。 |
error_code | int | 错误码。 |
charge_status | object | 充电状态对象。 |
joy_mode | int | 控制模式 (0:无, 1:导航, 2:手柄, 3:UWB)。 |
guardian_switch | bool | 停障开关状态。 |
guardian_velocity_decay_ratio | object | 障碍物检测速度衰减系数。 |
uwb_state | bool | UWB状态。 |
调用示例
python
from daystar_sdk.client import RobotClient
# 初始化客户端
with RobotClient(host='192.168.144.105', port=50051) as client:
# 机器人通用状态获取
success, common_status = client.get_common_status()
if success:
print(f"网络状态: {common_status.network}%")
print(f"机器人姿态: {common_status.belie_or_stand}")
print(f"急停状态: {common_status.emergency}")
print(f"避障状态: {common_status.avoidance}")
print(f"当前速度: {common_status.cur_speed}")
print(f"当前高度: {common_status.cur_height}")
print(f"驱动器状态: {common_status.driver_enable_state}")
print(f"当前场景: {common_status.cur_scene}")
print(f"控制模式: {common_status.joy_mode}")ROS2接口
获取运动状态信息
基本状态信息
该接口用于发布机器人的基本状态信息。
| Topic 名称 | Topic 类型 | 角色 |
|---|---|---|
/robot_state | std_msgs::msg::UInt32 | 发布方 |
消息结构
std_msgs::msg::UInt32 消息类型包含以下字段:
| 字段名称 | 类型 | 描述 |
|---|---|---|
data | uint32 | 机器人状态码。 |
状态码
| 值 | 描述 |
|---|---|
0 | 趴下 (lie down) |
1 | 正在站立 (standing up) |
2 | 站立 (stand up) |
7 | 无 (null) |
示例消息
cpp
std_msgs::msg::UInt32 state_msg;
state_msg.data = 2; // standup测试方法
bash
ros2 topic echo /robot_state当前控制模式
该接口用于发布机器人当前的控制模式。
| Topic 名称 | Topic 类型 | 角色 |
|---|---|---|
/control_mode | std_msgs::msg::UInt8 | 发布方 |
消息结构
std_msgs::msg::UInt8 消息类型包含以下字段:
| 字段名称 | 类型 | 描述 |
|---|---|---|
data | uint8 | 机器人控制模式状态码。 |
状态码描述
| 值 | 描述 |
|---|---|
0 | 手持遥控 |
1 | 自动(导航) |
示例消息
cpp
std_msgs::msg::UInt8 control_mode_msg;
control_mode_msg.data = 1; // 自动(导航)测试方法
bash
ros2 topic echo /control_mode当前步态
该接口用于发布机器人的当前步态。
| Topic 名称 | Topic 类型 | 角色 |
|---|---|---|
/gait | std_msgs::msg::UInt8 | 发布方 |
消息结构
std_msgs::msg::UInt8 消息类型包含以下字段:
| 字段名称 | 类型 | 描述 |
|---|---|---|
data | uint8 | 机器人当前步态码。 |
步态码
| 值 | 描述 |
|---|---|
0 | 正常步态 |
1 | 楼梯步态 |
2 | 斜坡步态 |
示例消息
cpp
std_msgs::msg::UInt8 gait_msg;
gait_msg.data = 2; // 斜坡步态测试方法
bash
ros2 topic echo /gaitC#接口
获取运动状态信息
void SubscribeMotionState(IMotionStateListener motionStateListener)
功能说明
订阅运动状态信息。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
motionStateListener | IMotionStateListener | 必填 | 运动状态监听接口。 |
回调接口说明
csharp
interface IMotionStateListener
{
/**
* @brief 回调正常运动信息
*
* @see MotionState 状态信息类
*/
void onMotionStateCallback(MotionState motionState);
/**
* @brief 回调异常错误信息
*/
void onMotionErrorCallback(string errorCode, string subErrorCode, int jointIndex);
}onMotionStateCallback 参数
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
motionState | MotionState | 必填 | 包含运动状态信息的对象。 |
MotionState 字段说明
| 字段 | 描述 |
|---|---|
RobotEnableState | 驱动器状态。 |
CurSpeed | 当前速度。 |
CurHeight | 当前高度。 |
CurScene | 当前场景。 |
MaxSpeed | 最大速度。 |
MaxHeight | 最大高度。 |
IsEmergency | 急停状态。 |
ControlType | 控制类型。 |
AvoidObstacle | 避障状态。 |
UWBState | UWB状态。 |
BionicActionState | 演示动作状态。 |
SceneSwitchState | 场景切换状态。 |
ObstacleDirection | 避障障碍物方向(float[4]数组:left、front、right、back四个方向,value < 0 代表此方向有障碍物)。 |
EStopState | 急停状态。 |
onMotionErrorCallback 参数
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
errorCode | string | 必填 | 主错误码。释义参考 《SDK概述》中故障章节。 |
subErrorCode | string | 必填 | 子错误码。为0xFFFFFFFF时可以忽略。 |
jointIndex | int | 必填 | 关节索引号。为-1时可以忽略。 |
返回值
| 类型 | 说明 |
|---|---|
void | 无。 |
void UnSubscribeMotionState()
功能说明
取消订阅运动状态信息。
参数说明
| 参数名 | 类型 | 必填/默认值 | 说明 |
|---|---|---|---|
| 无 | - | - | 无参数 |
返回值
| 类型 | 说明 |
|---|---|
void | 无。 |
调用示例
csharp
private RobotSDKManager _robotSDKManager;
private RobotStateListener _robotSystemState;
public class RobotSDKSample : MonoBehaviour, IConnectionStateListener, IMotionStateListener
{
void Start(){
_robotSDKManager = RobotSDKManager.Instance;
_robotSDKManager?.InitialRobot(RobotType.IS, "", "", this);
_robotSystemState = _robotSDKManager.CreateRobotBasicSystemState();
_robotSystemState?.SubscribeMotionState(this);
}
public void onConnected()
{
Debug.Log("robot connect success!");
}
public void onFailed()
{
Debug.Log("robot connect failed!");
}
public void onDisConnect()
{
Debug.Log("robot disconnect!");
}
public void onMotionStateCallback(MotionState motionState)
{
}
public void onMotionErrorCallback(int errorCode, string errorMessage)
{
}
void onDestroy(){
_robotSystemState?.UnSubscribeMotionState();
}
}