Skip to content

Motion Status Service Interface

Interface NameFunction OverviewC++PythonROSC#
Get Motion Status InfoError 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 NameTypeRequired/DefaultDescription
callbackMCSStatusCallbackRequiredMCS status callback function. Receives a complete status structure containing all MCS system statuses.

Callback Type Description

cpp
/**
* @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 NameTypeDescription
errorMessagestd::stringSystem error description.
heartBeatint64_tHeartbeat count, used to detect communication status.
sceneSceneTypeCurrent motion scene mode.
switchStateSceneSwitchStateTypeScene switching progress.
driverStateDriverEnableStateDriver enable status.
controllerModeControllerModeCurrent control mode (navigation/joystick).
guardianSwitchActiveboolSafety stop-guard function status (True: Activated, False: Off).
guardianVelocityDecayRatioGuardianVelocityDecayRatioVelocity decay coefficients in all directions (Obstacle detection).
motionMCSMotionInfoCurrent speed and height information.

SceneSwitchStateType Enum

ValueDescription
NULL_SCENEUnknown state (0).
SWITCHINGSwitching state (1).
SUCCEEDEDSwitch succeeded (2).
FAILEDError state (3).

DriverEnableState Enum

ValueDescription
UNKNOWNUnknown state (0).
ENABLEDEnabled (1).
ENABLINGEnabling (2).
ENABLE_FILEDEnable failed (3).
DISABLEDDisabled (4).

GuardianVelocityDecayRatio Structure

Field NameTypeDescription
left_ratiofloatLeft direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle).
front_ratiofloatFront direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle).
right_ratiofloatRight direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle).
rear_ratiofloatRear direction obstacle detection status (< 0: Obstacle, ≥ 0: No obstacle).

Return Value

TypeDescription
voidNone.

Usage Example

cpp
// 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_state must point to a valid common::ROBOT_COMMON_STATUS structure.

void setMotionCallback(MCSMotionCallback callback)

Function Description
Set MCS motion parameter callback (merged callback interface).

Parameter Description

Parameter NameTypeRequired/DefaultDescription
callbackMCSMotionCallbackRequiredMCS motion parameter callback function. Receives a motion parameter structure containing speed and height.

Callback Type Description

cpp
/**
* @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 NameTypeDescription
speedfloatCurrent speed percentage (0.0-1.0).
heightfloatCurrent height percentage (0.0-1.0).

Return Value

TypeDescription
voidNone.

Usage Example

cpp
// 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 NameTypeRequired/DefaultDescription
None--No parameters.

Return Value

TypeDescription
tupleReturns (success, common_status). success is boolean, common_status is an object containing status fields.

common_status Object Description

Field NameTypeDescription
networkintRobot current network status (0-100).
belie_or_standintCurrent posture (0:Unknown, 1:Lie down, 2:Switching, 3:Stand up).
emergencyboolWhether in emergency stop state.
avoidanceboolAutomatic obstacle avoidance status.
heartbeatint64Heartbeat count.
cur_speedfloatCurrent speed.
cur_heightfloatCurrent height.
max_speedfloatMaximum speed.
max_heightfloatMaximum height.
cur_scene_switch_stateintScene switching status (0:None, 1:Switching, 2:Success, 3:Failed).
cur_sceneintCurrent scene (0:None, 2:Walking Gait, 3:Stair Gait, 9:RL Gait, 10:Slope Gait, ...).
driver_enable_stateintDriver enable status (0:Unknown, 1:Enabled, 2:Enabling, 3:Failed, 4:Disabled).
error_codeintError code.
charge_statusobjectCharging status object.
joy_modeintControl mode (0:None, 1:Navigation, 2:Joystick, 3:UWB).
guardian_switchboolStop-guard switch status.
guardian_velocity_decay_ratioobjectObstacle detection velocity decay ratio.
uwb_stateboolUWB status.

Usage Example

python
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 NameTopic TypeRole
/robot_statestd_msgs::msg::UInt32Publisher

Message Structure

std_msgs::msg::UInt32 message type contains the following fields:

Field NameTypeDescription
datauint32Robot state code.

State Codes

ValueDescription
0Lie down
1Standing up
2Stand up
7Null

Example Message

cpp
std_msgs::msg::UInt32 state_msg;
state_msg.data = 2; // standup

Test Method

bash
ros2 topic echo /robot_state

Current Control Mode

This interface is used to publish the robot's current control mode.

Topic NameTopic TypeRole
/control_modestd_msgs::msg::UInt8Publisher

Message Structure

std_msgs::msg::UInt8 message type contains the following fields:

Field NameTypeDescription
datauint8Robot control mode code.

Control Mode Codes

ValueDescription
0Remote Control (Manual)
1Auto (Navigation)

Example Message

cpp
std_msgs::msg::UInt8 control_mode_msg;
control_mode_msg.data = 1; // Auto (Navigation)

Test Method

bash
ros2 topic echo /control_mode

Current Gait

This interface is used to publish the robot's current gait.

Topic NameTopic TypeRole
/gaitstd_msgs::msg::UInt8Publisher

Message Structure

std_msgs::msg::UInt8 message type contains the following fields:

Field NameTypeDescription
datauint8Robot current gait code.

Gait Codes

ValueDescription
0Normal Gait
1Stairs Gait
2Slope Gait

Example Message

cpp
std_msgs::msg::UInt8 gait_msg;
gait_msg.data = 2; // Slope Gait

Test Method

bash
ros2 topic echo /gait

C# Interface

Get Motion Status Information

void SubscribeMotionState(IMotionStateListener motionStateListener)

Function Description
Subscribe to motion status information.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
motionStateListenerIMotionStateListenerRequiredThe listener interface for motion status updates.

Callback Interface Description

csharp
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 NameTypeRequired/DefaultDescription
motionStateMotionStateRequiredObject containing motion status information.

MotionState Fields Description

FieldDescription
RobotEnableStateDriver status.
CurSpeedCurrent speed.
CurHeightCurrent height.
CurSceneCurrent scene.
MaxSpeedMaximum speed.
MaxHeightMaximum height.
IsEmergencyEmergency stop status.
ControlTypeControl type.
AvoidObstacleObstacle avoidance status.
UWBStateUWB status.
BionicActionStateDemo action status.
SceneSwitchStateScene switching status.
ObstacleDirectionObstacle direction (float[4]: left, front, right, back; value < 0 means obstacle present).
EStopStateE-Stop status.

onMotionErrorCallback Parameters

Parameter NameTypeRequired/DefaultDescription
errorCodestringRequiredMain error code. Refer to "SDK Overview" Faults section.
subErrorCodestringRequiredSub-error code. Can be ignored if 0xFFFFFFFF.
jointIndexintRequiredJoint index number. Can be ignored if -1.

Return Value

TypeDescription
voidNone.

void UnSubscribeMotionState()

Function Description
Unsubscribe from motion status information.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
None--No parameters.

Return Value

TypeDescription
voidNone.

Usage Example

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();
    }
}