Motion Status Service Interface
| Interface Name | Function Overview | C++ | Python | ROS | C# |
| Get Motion Status Info | Error Information | ✔ | ✔ | ✔ | |
| Communication Status | ✔ | ✔ | ✔ | ✔ | |
| Current Scene | ✔ | ✔ | ✔ | ✔ | |
| Scene Switching Status | ✔ | ✔ | ✔ | ||
| Driver State | ✔ | ✔ | ✔ | ||
| Control Mode | ✔ | ✔ | ✔ | ✔ | |
| Avoidance Status | ✔ | ✔ | ✔ | ||
| Current Speed | ✔ | ✔ | ✔ | ||
| Current Height | ✔ | ✔ | ✔ | ||
| Current Posture | ✔ | ✔ | ✔ | ✔ | |
| UWB Status | ✔ | ✔ | ✔ | ||
| E-Stop Status | ✔ | ✔ | ✔ |
C++ Interface
Get Motion Status Information
void setStatusCallback(MCSStatusCallback callback)
Function Description
Set MCS status callback (merged callback interface). This callback function is called when the MCS system status changes, containing complete robot status information.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
callback | MCSStatusCallback | Required | MCS status callback function. Receives a complete status structure containing all MCS system statuses. |
Callback Type Description
/**
* @brief MCS system status structure, containing all MCS-related status
*/
struct MCSStatusInfo
{
std::string errorMessage; ///< Error message
int64_t heartBeat; ///< Heartbeat value
SceneType scene; ///< Current scene
SceneSwitchStateType switchState; ///< Scene switching status
DriverEnableState driverState; ///< Enable status
ControllerMode controllerMode; ///< Control mode
bool guardianSwitchActive; ///< Stop-guard switch status
GuardianVelocityDecayRatio guardianVelocityDecayRatio; ///< Obstacle detection in all directions
MCSMotionInfo motion; ///< Motion parameters
/**
* @brief Default constructor
*/
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 Structure Description
| Field Name | Type | Description |
|---|---|---|
errorMessage | std::string | System error description. |
heartBeat | int64_t | Heartbeat count, used to detect communication status. |
scene | SceneType | Current motion scene mode. |
switchState | SceneSwitchStateType | Scene switching progress. |
driverState | DriverEnableState | Driver enable status. |
controllerMode | ControllerMode | Current control mode (navigation/joystick). |
guardianSwitchActive | bool | Safety stop-guard function status (True: Activated, False: Off). |
guardianVelocityDecayRatio | GuardianVelocityDecayRatio | Velocity decay coefficients in all directions (Obstacle detection). |
motion | MCSMotionInfo | Current speed and height information. |
SceneSwitchStateType Enum
| Value | Description |
|---|---|
NULL_SCENE | Unknown state (0). |
SWITCHING | Switching state (1). |
SUCCEEDED | Switch succeeded (2). |
FAILED | Error state (3). |
DriverEnableState Enum
| Value | Description |
|---|---|
UNKNOWN | Unknown state (0). |
ENABLED | Enabled (1). |
ENABLING | Enabling (2). |
ENABLE_FILED | Enable failed (3). |
DISABLED | Disabled (4). |
GuardianVelocityDecayRatio Structure
| Field Name | Type | Description |
|---|---|---|
left_ratio | float | Left direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle). |
front_ratio | float | Front direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle). |
right_ratio | float | Right direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle). |
rear_ratio | float | Rear direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle). |
Return Value
| Type | Description |
|---|---|
void | None. |
Usage Example
// MCS system status callback function
void onMCSStatusChanged(const MCSStatusInfo &status)
{
std::cout << "\n===== MCS SYSTEM STATUS UPDATE =====" << std::endl;
std::cout << "Error message: " << (status.errorMessage.empty() ? "None" : status.errorMessage) << std::endl;
std::cout << "Heartbeat: " << status.heartBeat << std::endl;
std::cout << "Current scene: " << sceneTypeToString(status.scene) << std::endl;
std::cout << "Enable status: " << driverEnableStateToString(status.driverState) << std::endl;
std::cout << "Stop-guard switch: " << (status.guardianSwitchActive ? "Activated" : "Off") << std::endl;
std::cout << "Motion speed: " << (status.motion.speed * 100) << "%" << std::endl;
std::cout << "Body height: " << (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);Notes
com_statemust point to a validcommon::ROBOT_COMMON_STATUSstructure.
void setMotionCallback(MCSMotionCallback callback)
Function Description
Set MCS motion parameter callback (merged callback interface).
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
callback | MCSMotionCallback | Required | MCS motion parameter callback function. Receives a motion parameter structure containing speed and height. |
Callback Type Description
/**
* @brief MCS motion status information structure, containing motion-related parameters
*/
struct MCSMotionInfo
{
float speed; ///< Current speed percentage (0.0-1.0)
float height; ///< Current height percentage (0.0-1.0)
/**
* @brief Default constructor
*/
MCSMotionInfo() : speed(0.0f), height(0.0f) {}
/**
* @brief Constructor with parameters
*/
MCSMotionInfo(float spd, float hgt) : speed(spd), height(hgt) {}
};MCSMotionInfo Structure Description
| Field Name | Type | Description |
|---|---|---|
speed | float | Current speed percentage (0.0-1.0). |
height | float | Current height percentage (0.0-1.0). |
Return Value
| Type | Description |
|---|---|
void | None. |
Usage Example
// MCS motion parameter callback function
void onMCSMotionChanged(const MCSMotionInfo &motion)
{
std::cout << "\n--- Motion Parameter Update ---" << std::endl;
std::cout << "Speed: " << (motion.speed * 100) << "%" << std::endl;
std::cout << "Height: " << (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 Interface
Get Motion Status Information
tuple get_common_status()
Function Description
Get robot general status information.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
| None | - | - | No parameters. |
Return Value
| Type | Description |
|---|---|
tuple | Returns (success, common_status). success is boolean, common_status is an object containing status fields. |
common_status Object Description
| Field Name | Type | Description |
|---|---|---|
network | int | Robot current network status (0-100). |
belie_or_stand | int | Current posture (0:Unknown, 1:Lie down, 2:Switching, 3:Stand up). |
emergency | bool | Whether in emergency stop state. |
avoidance | bool | Automatic obstacle avoidance status. |
heartbeat | int64 | Heartbeat count. |
cur_speed | float | Current speed. |
cur_height | float | Current height. |
max_speed | float | Maximum speed. |
max_height | float | Maximum height. |
cur_scene_switch_state | int | Scene switching status (0:None, 1:Switching, 2:Success, 3:Failed). |
cur_scene | int | Current scene (0:None, 2:Walking Gait, 3:Stair Gait, 9:RL Gait, 10:Slope Gait, ...). |
driver_enable_state | int | Driver enable status (0:Unknown, 1:Enabled, 2:Enabling, 3:Failed, 4:Disabled). |
error_code | int | Error code. |
charge_status | object | Charging status object. |
joy_mode | int | Control mode (0:None, 1:Navigation, 2:Joystick, 3:UWB). |
guardian_switch | bool | Stop-guard switch status. |
guardian_velocity_decay_ratio | object | Obstacle detection velocity decay ratio. |
uwb_state | bool | UWB status. |
Usage Example
from daystar_sdk.client import RobotClient
# Initialize client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Get robot general status
success, common_status = client.get_common_status()
if success:
print(f"Network Status: {common_status.network}%")
print(f"Robot Posture: {common_status.belie_or_stand}")
print(f"E-Stop Status: {common_status.emergency}")
print(f"Avoidance Status: {common_status.avoidance}")
print(f"Current Speed: {common_status.cur_speed}")
print(f"Current Height: {common_status.cur_height}")
print(f"Driver Status: {common_status.driver_enable_state}")
print(f"Current Scene: {common_status.cur_scene}")
print(f"Control Mode: {common_status.joy_mode}")ROS2 Interface
Get Motion Status Information
Basic Status Information
This interface is used to publish the robot's basic status information.
| Topic Name | Topic Type | Role |
|---|---|---|
/robot_state | std_msgs::msg::UInt32 | Publisher |
Message Structure
std_msgs::msg::UInt32 message type contains the following fields:
| Field Name | Type | Description |
|---|---|---|
data | uint32 | Robot state code. |
State Codes
| Value | Description |
|---|---|
0 | Lie down |
1 | Standing up |
2 | Stand up |
7 | Null |
Example Message
std_msgs::msg::UInt32 state_msg;
state_msg.data = 2; // standupTest Method
ros2 topic echo /robot_stateCurrent Control Mode
This interface is used to publish the robot's current control mode.
| Topic Name | Topic Type | Role |
|---|---|---|
/control_mode | std_msgs::msg::UInt8 | Publisher |
Message Structure
std_msgs::msg::UInt8 message type contains the following fields:
| Field Name | Type | Description |
|---|---|---|
data | uint8 | Robot control mode code. |
Control Mode Codes
| Value | Description |
|---|---|
0 | Remote Control (Manual) |
1 | Auto (Navigation) |
Example Message
std_msgs::msg::UInt8 control_mode_msg;
control_mode_msg.data = 1; // Auto (Navigation)Test Method
ros2 topic echo /control_modeCurrent Gait
This interface is used to publish the robot's current gait.
| Topic Name | Topic Type | Role |
|---|---|---|
/gait | std_msgs::msg::UInt8 | Publisher |
Message Structure
std_msgs::msg::UInt8 message type contains the following fields:
| Field Name | Type | Description |
|---|---|---|
data | uint8 | Robot current gait code. |
Gait Codes
| Value | Description |
|---|---|
0 | Normal Gait |
1 | Stairs Gait |
2 | Slope Gait |
Example Message
std_msgs::msg::UInt8 gait_msg;
gait_msg.data = 2; // Slope GaitTest Method
ros2 topic echo /gaitC# Interface
Get Motion Status Information
void SubscribeMotionState(IMotionStateListener motionStateListener)
Function Description
Subscribe to motion status information.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
motionStateListener | IMotionStateListener | Required | The listener interface for motion status updates. |
Callback Interface Description
interface IMotionStateListener
{
/**
* @brief Callback for normal motion information
*
* @see MotionState Status information class
*/
void onMotionStateCallback(MotionState motionState);
/**
* @brief Callback for abnormal error information
*/
void onMotionErrorCallback(string errorCode, string subErrorCode, int jointIndex);
}onMotionStateCallback Parameters
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
motionState | MotionState | Required | Object containing motion status information. |
MotionState Fields Description
| Field | Description |
|---|---|
RobotEnableState | Driver status. |
CurSpeed | Current speed. |
CurHeight | Current height. |
CurScene | Current scene. |
MaxSpeed | Maximum speed. |
MaxHeight | Maximum height. |
IsEmergency | Emergency stop status. |
ControlType | Control type. |
AvoidObstacle | Obstacle avoidance status. |
UWBState | UWB status. |
BionicActionState | Demo action status. |
SceneSwitchState | Scene switching status. |
ObstacleDirection | Obstacle direction (float[4]: left, front, right, back; value < 0 means obstacle present). |
EStopState | E-Stop status. |
onMotionErrorCallback Parameters
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
errorCode | string | Required | Main error code. Refer to "SDK Overview" Faults section. |
subErrorCode | string | Required | Sub-error code. Can be ignored if 0xFFFFFFFF. |
jointIndex | int | Required | Joint index number. Can be ignored if -1. |
Return Value
| Type | Description |
|---|---|
void | None. |
void UnSubscribeMotionState()
Function Description
Unsubscribe from motion status information.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
| None | - | - | No parameters. |
Return Value
| Type | Description |
|---|---|
void | None. |
Usage Example
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();
}
}