Skip to content

Creating a Client Application

This tutorial will guide you step-by-step on how to create your own high-level application using the Daystar Bot SDK.

With the Daystar Bot SDK, developers can build a wide range of high-level control applications for the robot.
In this section, we will walk you through the process of writing a simple program that makes the Daystar Bot stand up and walk forward for a short distance.

Accessing the SDK Interfaces

The header files lenovo-daystar-sdk/lenovo_daystar_*.h are provided by the Daystar Bot SDK. By calling the high-level APIs defined in these headers, you can control the Daystar Bot to perform specific actions.

These interface header files are included in the SDK package at the following paths:
install/include/lenovo-daystar-sdk/lenovo_daystar_sdk.h andinstall/include/lenovo-daystar-sdk/lenovo_daystar_sport.h.

Refer to the sections below for details on the available interfaces.

cpp
#ifndef LENOVO_DAYSTAR_SDK_H
#define LENOVO_DAYSTAR_SDK_H

#include <memory>
#include <string>
#include <functional>

// Include subsystem declarations
#include "lenovo_daystar_sport.h"
#include "lenovo_daystar_rps.h"
#include "lenovo_daystar_ptz.h"

// #include "lenovo_daystar_router.h"

// Note: Internal implementation headers are no longer included.
// This ensures that users can use the SDK without requiring a gRPC environment.

namespace Lenovo
{
    namespace Daystar
    {

        // Forward declaration
        class RobotClientImpl;

        /**
         * @brief The main class of the Daystar SDK, serving as the unified entry point for all functionalities.
         *
         * This class wraps the underlying RobotClient and provides access to the Sport, RPS, and Router subsystems.
         */
        class SDK
        {
        public:
            /**
             * @brief Constructor. Connects to the robot services at the specified address.
             *
             * @param motion_server_address Address of the motion control service (format: "IP:Port")
             * @param perception_server_address Address of the perception service
             */
            explicit SDK(const std::string &motion_server_address = "192.168.144.103:50051",
                         const std::string &perception_server_address = "192.168.100.105");

            /**
             * @brief Destructor
             */
            ~SDK();

            /**
             * @brief Get the Sport subsystem interface.
             *
             * @return Reference to the Sport subsystem
             */
            class Sport &getSport();

            /**
             * @brief Get the RPS (Robot Perception System) subsystem interface.
             *
             * @return Reference to the RPS subsystem
             */
            class RPS &getRPS();

            /**
             * @brief Get the PTZ (Pan-Tilt-Zoom) subsystem interface.
             *
             * @return Reference to the PTZ subsystem
             */
            class PTZ &getPTZ();

            /**
             * @brief Get the Router subsystem interface.
             *
             * @return Reference to the Router subsystem
             * @note Router functionality is currently not available in this version.
             */
            // class Router &getRouter();

            /**
             * @brief Check the connection status with the backend server.
             *
             * @return True if connected; otherwise, false.
             */
            bool isConnected() const;

            /**
             * @brief Get the server name.
             *
             * @return Server name, or an empty string if not connected.
             */
            std::string getServerName() const;

            /**
             * @brief Get the server version.
             *
             * @return Server version, or an empty string if not connected.
             */
            std::string getServerVersion() const;

            /**
             * @brief Generic call interface for invoking arbitrary backend methods.
             *
             * @param method_name Name of the method to invoke
             * @param params Key-value map of parameters
             * @param request_id Optional request ID for tracking; autogenerated if empty
             * @param metadata Optional additional metadata
             * @return Result of the call as a GenericCallResponse object
             */
            GenericCallResponse genericCall(
                const std::string &method_name,
                const std::map<std::string, std::any> &params,
                const std::string &request_id = "",
                const std::map<std::string, std::string> &metadata = {});

        private:
            std::unique_ptr<RobotClientImpl> impl_; // Internal implementation
            std::unique_ptr<PTZ> ptz_;
        };

    } // namespace Daystar
} // namespace Lenovo

#endif // LENOVO_DAYSTAR_SDK_H
cpp
#ifndef LENOVO_DAYSTAR_SPORT_H
#define LENOVO_DAYSTAR_SPORT_H

#include <memory>
#include <string>
#include <functional>
#include "lenovo-daystar-sdk/lenovo_daystar_types.h"

namespace Lenovo
{
    namespace Daystar
    {

        // Forward declarations
        class RobotClientImpl;
        class SportImpl;

        /**
         * @brief Sport subsystem class that wraps McsClient functionality
         *
         * This class provides robot motion control functions and hides gRPC implementation details.
         */
        class Sport
        {
        public:
            /**
             * @brief Constructor
             *
             * @param impl Internal implementation pointer
             */
            explicit Sport(RobotClientImpl *impl);

            /**
             * @brief Destructor
             */
            ~Sport();

            /**
             * @brief Set MCS status callback (merged interface)
             *
             * This callback is triggered when the MCS system status changes, containing complete robot status info.
             * Includes:
             * - heartBeat: for communication monitoring
             * - scene: current motion scene mode
             * - switchState: scene switching progress
             * - driverState: driver enable status
             * - joyMode: current control mode (navigation/joystick)
             * - guardianSwitchActive: safety stop switch status
             * - guardianVelocityDecayRatio: velocity attenuation coefficients
             * - motion: current speed and height
             * - maxSpeed: max robot speed (m/s)
             * - errorMessage: system error description
             *
             * @param callback Callback function receiving MCSStatusInfo
             * @note The callback is executed in a background thread; ensure thread safety.
             * @see MCSStatusInfo
             */
            void setStatusCallback(MCSStatusCallback callback);

            /**
             * @brief Set MCS motion parameter callback (merged interface)
             *
             * This callback is triggered when motion parameters change, including:
             * - speed: real-time speed (range 0.0–1.0)
             * - height: real-time height (range 0.0–1.0)
             *
             * @param callback Callback receiving MCSMotionInfo
             * @note The callback is executed in a background thread; ensure thread safety.
             * @see MCSMotionInfo
             */
            void setMotionCallback(MCSMotionCallback callback);

            /**
             * @brief Clear driver error for selected joints
             *
             * @param mask Joint selection mask
             * @return true if success, false otherwise
             */
            bool clearDriverError(uint32_t joint_mask);

            /**
             * @brief Recalibrate and save all drivers
             * @todo To be removed
             *
             * @param enable Whether to enable calibration
             * @return true if successful
             */
            bool reCalibrateAllDriverAndSave(bool enable);

            /**
             * @brief Zero the joint torque sensors
             * @todo To be removed
             *
             * @param from Specifies the control mode (navigation or joystick)
             * @return true if successful
             */
            bool ZeroTorqueSensor();

            /**
             * @brief Enable or disable the robot drivers
             *
             * @param enable true to enable
             * @return true if successful
             */
            bool enableDriver(bool enable);

            /**
             * @brief Make the robot lie down or stand up
             *
             * @param lieDown true = lie down, false = stand up
             * @return true if successful
             */
            bool lieDownOrStandUp(bool lieDown);

            /**
             * @brief Directional motion control
             *
             * Controls the robot movement in 3 DOF: forward-backward, lateral, and rotation.
             *
             * Parameter range and direction:
             * - Valid range: -1.0 ≤ (x, y, yaw) ≤ 1.0
             * - Positive/negative meanings:
             *   * x > 0: forward; x < 0: backward
             *   * y > 0: left; y < 0: right
             *   * yaw > 0: CCW rotation; yaw < 0: CW rotation
             *
             * Actual speed = x/y/yaw × maxSpeed × percent / 100
             *
             * Safety mechanism:
             * - Must be called continuously to maintain motion (≥5Hz, recommend 10–20Hz)
             * - Timeout after 200ms leads to auto stop
             *
             * Example usage:
             * ```cpp
             * sport.adjustSpeed(50);  // Set speed scale
             * while (need_to_move) {
             *     sport.move(0.5f, 0.0f, 0.0f);
             *     std::this_thread::sleep_for(std::chrono::milliseconds(50));
             * }
             * sport.move(0.0f, 0.0f, 0.0f);  // Explicit stop
             * ```
             *
             * @param x Forward/backward, range [-1.0, 1.0]
             * @param y Left/right, range [-1.0, 1.0]
             * @param yaw Rotation, range [-1.0, 1.0]
             * @return true if successful
             * @warning Must be called within 200ms intervals or motion stops
             * @note Suggest 10–20Hz calling frequency
             */
            bool move(float x, float y, float yaw);

            /**
             * @brief Adjust body height
             *
             * @param percent Height percentage [0, 100]
             * @return true if successful
             */
            bool adjustBodyHeight(int percent);

            /**
             * @brief Adjust speed scale
             *
             * Sets the global motion speed scale affecting all movement commands.
             *
             * Speed = move() × maxSpeed × (percent / 100)
             *
             * Example:
             * ```cpp
             * sport.adjustSpeed(30); // 30% speed
             * sport.move(1.0f, 0.0f, 0.0f);
             * ```
             *
             * @param percent Speed percent [0–100]
             * @return true if successful
             * @note Use lower speed in test environments
             */
            bool adjustSpeed(int percent);

            /**
             * @brief Set robot scene
             *
             * @param sceneType Scene enum
             * @return true if successful
             */
            bool setScene(SceneType sceneType);

            /**
             * @brief Automatic recovery
             * @todo To be removed
             *
             * @return true if successful
             */
            bool selfRecovery();

            /**
             * @brief Emergency stop
             *
             * @return true if successful
             */
            bool emergencyStop();

            /**
             * @brief Resume from emergency stop
             *
             * @return true if successful
             */
            bool resumeFromEmergencyStop();

            /**
             * @brief Set navigation or joystick mode
             *
             * @param controllerMode ControllerMode enum
             * @return true if successful
             */
            bool setControlMode(Lenovo::Daystar::ControllerMode controllerMode);

            /**
             * @brief Enter or exit charging mode
             * @todo To be removed
             *
             * @param enter true to enter, false to exit
             * @return true if successful
             */
            bool enterOrExitCharge(bool enter);

            /**
             * @brief Enable or disable guardian stop switch
             *
             * @param enable true = enable
             * @return true if successful
             */
            bool setGuardianSwitch(bool enable);

            /**
             * @brief Demo motion control
             *
             * @param demoType Type of demo
             * @param enable true to start, false to stop
             * @return true if successful
             */
            bool demoControl(int demoType, bool enable = false);

            /**
             * @brief Clear latest error message
             */
            void ClearLatestHistory();

            /**
             * @brief Get MC firmware version
             *
             * @param mcIndex Index of MC
             * @return Version string or empty if failed
             */
            std::string getMcVersion(int mcIndex = 0);

            /**
             * @brief Get robot name
             *
             * @param mcIndex Index of MC
             * @return Name string or empty if failed
             */
            std::string getRobotName(int mcIndex = 0);

        private:
            std::unique_ptr<SportImpl> impl_; // Internal implementation
        };

    } // namespace Daystar
} // namespace Lenovo

#endif // LENOVO_DAYSTAR_SPORT_H

The following functions are used in the implementation described above:

  1. explicit SDK(const std::string &server_address = "192.168.144.103:50051");Default SDK constructor
  2. Sport &SDK::getSport();Get motion control subsystem
  3. bool Sport::enableDriver(bool enable);Enable driver
  4. bool Sport::lieDownOrStandUp(bool enable);Set robot posture
  5. bool Sport::setScene(Lenovo::Daystar::SceneType sceneType);Set robot scene
  6. bool Sport::adjustSpeed(int percent);Set robot movement speed factor
  7. bool Sport::move(float x, float y, float yaw);Control robot movement
  8. void Sport::setMotionCallback(MCSMotionCallback callback) and void Sport::setStatusCallback(MCSStatusCallback callback)Set status callbacks

Create Application Files

Next, integrate the SDK to create your own application project.
Assume the working directory is /home/daystar/sdk_test_project.
Execute the following commands in sequence. Copy the SDK .so library files and .h header files into the corresponding directories of your application project (select either the ARM or x86 version of the SDK .so library depending on your development platform).
Then, create the app_test.cpp file and write the code to call SDK interfaces and implement your application logic.

bash
cd /home/daystar/sdk_test_project
mkdir include src lib
cp /sdk/install/include/* include/
cp /sdk/install/lib/* lib/
cd src
touch app_test.cpp

Next, let's edit app_test.cpp

  1. Include the header file:
cpp
#include "lenovo-daystar-sdk/lenovo_daystar_sdk.h"
  1. Call SDK functions to implement application logic.
cpp
Lenovo::Daystar::SDK sdk; // Construct the SDK
auto &sport = sdk.getSport(); // Get the motion control client
sport.enableDriver(true); // Enable the driver
sport.lieDownOrStandUp(true); // Stand up
sport.adjustSpeed(50); // Set the maximum speed

for (int i = 0; i < 20; ++i) { // Move forward at speed 0.3 for 2 seconds
  sport.move(0.3, 0.0, 0.0);
  std::this_thread::sleep_for(std::chrono::milliseconds(100));
}

sport.lieDownOrStandUp(false); // Lie down
sport.enableDriver(false); // Disable the driver
cpp
#include "lenovo-daystar-sdk/lenovo_daystar_sdk.h"
#include "lenovo-daystar-sdk/lenovo_daystar_types.h"
#include <iostream>
#include <chrono>
#include <thread>
#include <string>
#include <sstream>
#include <cmath>

void printSportMenu()
{
    std::cout << "\n========== Sport Control Menu ==========" << std::endl;
    std::cout << "1.  Check connection status" << std::endl;
    std::cout << "2.  Get server info" << std::endl;
    std::cout << "3.  Enable driver" << std::endl;
    std::cout << "4.  Disable driver" << std::endl;
    std::cout << "5.  Robot lie down" << std::endl;
    std::cout << "6.  Robot stand up" << std::endl;
    std::cout << "7.  Set scene mode" << std::endl;
    std::cout << "8.  Adjust speed" << std::endl;
    std::cout << "9.  Move robot" << std::endl;
    std::cout << "10. Rotate robot" << std::endl;
    std::cout << "11. Stop motion" << std::endl;
    std::cout << "12. Set body posture" << std::endl;
    std::cout << "13. Set gait parameters" << std::endl;
    std::cout << "14. Get motion status" << std::endl;
    std::cout << "15. Get system status" << std::endl;
    std::cout << "16. Set status callback" << std::endl;
    std::cout << "17. Set motion callback" << std::endl;
    std::cout << "18. Get heartbeat value" << std::endl;
    std::cout << "19. General call test" << std::endl;
    std::cout << "0.  Exit program" << std::endl;
    std::cout << "=========================================" << std::endl;
    std::cout << "Please choose an operation (0-19): ";
}

float getFloatInput(const std::string &prompt)
{
    float value;
    std::cout << prompt;
    std::cin >> value;
    return value;
}

int getIntInput(const std::string &prompt)
{
    int value;
    std::cout << prompt;
    std::cin >> value;
    return value;
}

bool getBoolInput(const std::string &prompt)
{
    int value;
    std::cout << prompt << " (1=Yes, 0=No): ";
    std::cin >> value;
    return value != 0;
}

std::string getStringInput(const std::string &prompt)
{
    std::string value;
    std::cout << prompt;
    std::cin.ignore();
    std::getline(std::cin, value);
    return value;
}

void printMCSMotionInfo(const Lenovo::Daystar::MCSMotionInfo &info)
{
    std::cout << "Motion status info:" << std::endl;
    std::cout << "  Speed: " << info.speed << " (0.0-1.0)" << std::endl;
    std::cout << "  Height: " << info.height << " (0.0-1.0)" << std::endl;
}

void printMCSStatusInfo(const Lenovo::Daystar::MCSStatusInfo &info)
{
    std::cout << "System status info:" << std::endl;
    std::cout << "  Error Code: " << info.errorCode.error_code << std::endl;
    std::cout << "  Scene: " << static_cast<int>(info.scene) << std::endl;
    std::cout << "  Scene Switch Status: " << static_cast<int>(info.switchState) << std::endl;
    std::cout << "  Driver Enable Status: " << static_cast<int>(info.driverState) << std::endl;
    std::cout << "  Control Mode: " << static_cast<int>(info.controllerMode) << std::endl;
    std::cout << "  Guardian Switch: " << (info.guardianSwitchActive ? "Enabled" : "Disabled") << std::endl;
    std::cout << "  Obstacle Detection Ratios:" << std::endl;
    std::cout << "    Front: " << info.guardianVelocityDecayRatio.front_ratio << std::endl;
    std::cout << "    Left: " << info.guardianVelocityDecayRatio.left_ratio << std::endl;
    std::cout << "    Right: " << info.guardianVelocityDecayRatio.right_ratio << std::endl;
    std::cout << "    Rear: " << info.guardianVelocityDecayRatio.rear_ratio << std::endl;
}

int main()
{
    std::cout << "Sport interactive control program started..." << std::endl;

    try
    {
        // Create SDK instance
        Lenovo::Daystar::SDK sdk("192.168.100.103:50051");

        // Get Sport subsystem
        Lenovo::Daystar::Sport &sport = sdk.getSport();

        // Global variables to store callback data
        Lenovo::Daystar::MCSMotionInfo latest_motion;
        Lenovo::Daystar::MCSStatusInfo latest_status;

        int choice;
        bool running = true;

        while (running)
        {
            printSportMenu();
            std::cin >> choice;

            switch (choice)
            {
            case 0:
                running = false;
                std::cout << "Exiting program..." << std::endl;
                break;

            case 1:
            {
                if (sdk.isConnected())
                {
                    std::cout << "✓ Robot is connected" << std::endl;
                }
                else
                {
                    std::cout << "✗ Robot is not connected" << std::endl;
                }
                break;
            }

            case 2:
            {
                std::cout << "Server Name: " << sdk.getServerName() << std::endl;
                std::cout << "Server Version: " << sdk.getServerVersion() << std::endl;
                break;
            }

            case 3:
            {
                bool enabled = getBoolInput("Enable driver?");
                if (sport.enableDriver(enabled))
                {
                    std::cout << "✓ Driver " << (enabled ? "enabled" : "disabled") << " successfully" << std::endl;
                }
                else
                {
                    std::cout << "✗ Driver operation failed" << std::endl;
                }
                break;
            }

            case 4:
            {
                if (sport.enableDriver(false))
                {
                    std::cout << "✓ Driver disabled" << std::endl;
                }
                else
                {
                    std::cout << "✗ Driver disable failed" << std::endl;
                }
                break;
            }

            case 5:
            {
                if (sport.lieDownOrStandUp(false))
                { // false = lie down
                    std::cout << "✓ Robot is standing up" << std::endl;
                }
                else
                {
                    std::cout << "✗ Failed to stand up" << std::endl;
                }
                break;
            }

            case 6:
            {
                if (sport.lieDownOrStandUp(true))
                { // true = stand up
                    std::cout << "✓ Robot is lying down" << std::endl;
                }
                else
                {
                    std::cout << "✗ Failed to lie down" << std::endl;
                }
                break;
            }

            case 7:
            {
                std::cout << "Available scenes:" << std::endl;
                std::cout << "  0 - IDLE" << std::endl;
                std::cout << "  1 - WALKING" << std::endl;
                std::cout << "  2 - TROTTING" << std::endl;
                std::cout << "  3 - CLIMBING_STAIRS" << std::endl;
                std::cout << "  4 - SPECIAL" << std::endl;

                int scene = getIntInput("Select scene mode (0-4): ");
                if (sport.setScene(static_cast<Lenovo::Daystar::SceneType>(scene)))
                {
                    std::cout << "✓ Scene set successfully" << std::endl;
                }
                else
                {
                    std::cout << "✗ Scene setting failed" << std::endl;
                }
                break;
            }

            case 8:
            {
                int speed = getIntInput("Enter speed percentage (0-100): ");
                if (sport.adjustSpeed(speed))
                {
                    std::cout << "✓ Speed adjusted: " << speed << "%" << std::endl;
                }
                else
                {
                    std::cout << "✗ Speed adjustment failed" << std::endl;
                }
                break;
            }

            case 9:
            {
                float x = getFloatInput("Enter X direction speed (m/s): ");
                float y = getFloatInput("Enter Y direction speed (m/s): ");
                float z = getFloatInput("Enter angular speed (rad/s): ");
                if (sport.move(x, y, z))
                {
                    std::cout << "✓ Move command sent: (" << x << ", " << y << ", " << z << ")" << std::endl;
                }
                else
                {
                    std::cout << "✗ Move command failed" << std::endl;
                }
                break;
            }

            case 10:
            {
                float angular_speed = getFloatInput("Enter rotation speed (rad/s): ");
                if (sport.move(0.0f, 0.0f, angular_speed))
                {
                    std::cout << "✓ Rotation command sent: " << angular_speed << " rad/s" << std::endl;
                }
                else
                {
                    std::cout << "✗ Rotation command failed" << std::endl;
                }
                break;
            }

            case 11:
            {
                if (sport.move(0.0f, 0.0f, 0.0f))
                {
                    std::cout << "✓ Robot stopped moving" << std::endl;
                }
                else
                {
                    std::cout << "✗ Stop command failed" << std::endl;
                }
                break;
            }

            case 12:
            {
                std::cout << "⚠️  Body posture control not available yet" << std::endl;
                std::cout << "Please use other available functions" << std::endl;
                break;
            }

            case 13:
            {
                std::cout << "⚠️  Gait parameter setting not available yet" << std::endl;
                std::cout << "Please use other available functions" << std::endl;
                break;
            }

            case 14:
            {
                std::cout << "Current motion status:" << std::endl;
                printMCSMotionInfo(latest_motion);
                break;
            }

            case 15:
            {
                std::cout << "Current system status:" << std::endl;
                printMCSStatusInfo(latest_status);
                break;
            }

            case 16:
            {
                sport.setStatusCallback([&latest_status](const Lenovo::Daystar::MCSStatusInfo &status)
                                        {
                        latest_status = status;
                        std::cout << "[Callback] System status updated" << std::endl;
                        printMCSStatusInfo(status); });
                std::cout << "✓ Status callback set" << std::endl;
                break;
            }

            case 17:
            {
                sport.setMotionCallback([&latest_motion](const Lenovo::Daystar::MCSMotionInfo &motion)
                                        {
                        latest_motion = motion;
                        std::cout << "[Callback] Motion status updated" << std::endl;
                        printMCSMotionInfo(motion); });
                std::cout << "✓ Motion callback set" << std::endl;
                break;
            }

            case 18:
            {
                std::cout << "Current heartbeat value: " << latest_status.heartBeat << std::endl;
                break;
            }

            case 19:
            {
                std::cout << "Test general call - Get robot status" << std::endl;
                std::map<std::string, std::any> params;
                auto response = sdk.genericCall("GetRobotStatus", params);
                std::cout << "General call result:" << std::endl;
                std::cout << "  Success: " << (response.success ? "Yes" : "No") << std::endl;
                std::cout << "  Request ID: " << response.request_id << std::endl;
                std::cout << "  Error Message: " << response.error_message << std::endl;
                break;
            }

            default:
                std::cout << "✗ Invalid choice, please try again!" << std::endl;
                break;
            }

            // Wait briefly to allow callback messages to print
            std::this_thread::sleep_for(std::chrono::milliseconds(100));
        }
    }
    catch (const std::exception &e)
    {
        std::cerr << "Error: " << e.what() << std::endl;
        return 1;
    }

    std::cout << "Sport control program exited!" << std::endl;
    return 0;
}

Compile the Application File

After completing the application logic, proceed to compile the application file.
Edit the sdk_test_project/CMakeLists.txt file to add the compilation commands and include the example you just wrote, so that the corresponding executable file can be generated.
Finally, save the file.

cpp
cmake_minimum_required(VERSION 3.10)

project(sdk_test_project)

# Set C++ standard
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

set(ROBOT_CLIENT_LIB $1{CMAKE_CURRENT_LIST_DIR}/lib/liblenovo_daystar_sdk.so)

# Add executable
add_executable(app_test src/app_test.cpp)

# Link libraries
target_link_libraries(app_test
    $1{ROBOT_CLIENT_LIB}
)

# Include directories
target_include_directories(app_test PRIVATE
    ${CMAKE_CURRENT_SOURCE_DIR}
    ${CMAKE_CURRENT_LIST_DIR}/include
)

Finally, compile and run the example program.

bash
cd /home/daystar/sdk_test_project
mkdir build
cd build
cmake ..
make

Run the Application

Connect your development device to the robot's Wi-Fi network (e.g., IS_Plus_001), and ensure both are in the same local area network (LAN). Then, open a terminal and execute the following commands step by step to run the application. Follow the terminal prompts and press Enter when required.

bash
cd /home/daystar/sdk_test_project/build
sudo ./app_test

WARNING

Note: This application sends control commands to the Daystar Bot via the motion control service.
Please make sure the robot is running properly before executing this application.
For details, refer to the section App Binding.

Create a Custom Application (Python)

This section guides users on how to create their own high-level application using the Daystar Bot SDK in a Python environment.

(Currently supports Python 3.10 or above)

Programming Interfaces

Below are the core programming interfaces of the SDK Python Client, which can be used in your custom Python applications:

python
from daystar_sdk.client import RobotClient
import time
import logging

# Use context manager to automatically handle connection
with RobotClient(host='192.168.144.103', port=50051) as client:
    # Query system info
    success, version = client.get_mc_version()
    success, name = client.get_robot_name()
    
    # RPS-related operations
    success, battery_level, message = client.rps_get_battery_level()
    print(f"Battery level: {battery_level}%")
    
    success, message = client.set_rps_light_style(2)  # Breathing light
    time.sleep(2) 
    
    # MCS motion control
    success = client.driver_enable(True)         # Enable driver
    time.sleep(1)
    success = client.lie_down_or_stand_up(True)  # Stand up
    time.sleep(3)
    success = client.set_guardian_switch(True)   # Enable obstacle avoidance
    time.sleep(1)
    success = client.body_height_adjust(41)      # Adjust body height to 41%, max for IS is 41
    time.sleep(2)
    success = client.speed_adjust(34)            # Set speed to 34%, IS default is 34
    time.sleep(2)
    success = client.set_scene(2)                # Set walking scene
    time.sleep(2)
    success = client.direction_movement(linear_x=0.3)  # Move forward
    time.sleep(3)  # Wait for movement to complete
    success = client.direction_movement(linear_x=0.0)  # Stop moving forward
    time.sleep(1)
    success = client.direction_movement(angular_z=0.4)  # Rotate
    time.sleep(3)  # Wait for rotation to complete
    success = client.direction_movement(angular_z=0.0)  # Stop rotating
    time.sleep(2) 
    
    # Function switch
    success = client.demo_control(2, True)               # Enable demo mode 2: waving
    time.sleep(15) 
    
    # Status query
    success, common_status = client.get_common_status()
    if success:
        logging.info(f"Network status: {common_status.network}%")
        logging.info(f"Robot posture: {'Standing' if common_status.belie_or_stand == 3 else 'Lying down'}")
        logging.info(f"Emergency stop: {'Activated' if common_status.emergency else 'Not activated'}")
        logging.info(f"Obstacle avoidance: {'Enabled' if common_status.guardian_switch else 'Disabled'}")
        logging.info(f"Current speed: {common_status.cur_speed}")
        logging.info(f"Current height: {common_status.cur_height}")
        logging.info(f"Driver status: {'Enabled' if common_status.driver_enable_state == 1 else 'Disabled'}")
        logging.info(f"Current scene: {common_status.cur_scene}")
    time.sleep(1)

    success = client.lie_down_or_stand_up(False)  # Lie down
    time.sleep(5)

    # Disable driver
    logging.info("Disabling driver... Dangerous operation. Please ensure the robot is lying down and the surroundings are clear. Type 'DISABLE DRIVER' to confirm.")
    success, common_status = client.get_common_status()
    if common_status.belie_or_stand == 3:
        logging.error("Robot is not lying down. Canceling driver disable operation.")
    else:
        user_input = input("Please enter confirmation: ")
        if user_input == "DISABLE DRIVER":
            success = client.driver_enable(False)
            if success:
                logging.info("Driver has been disabled.")
            else:
                logging.error("Failed to disable driver.")
        else:
            logging.error("No confirmation entered. Canceling driver disable operation. You may press the emergency stop button to force the robot to lie down.")
    time.sleep(1)

WARNING

Note: For the complete example code, please refer to motion_demo.py and perception_demo.py under the examples directory.