High-Level Motion Service Interfaces
Introduction
High-Level Control Interfaces:
You can send motion commands such as velocity control and posture control to the Saturn Robot by invoking ROS2 Topics, ROS2 Services, C++ functions, or Python functions.
| Purpose | C++ | ROS | Python | C# | Java |
|---|---|---|---|---|---|
| Initialization | ✔ | ✔ | ✔ | ✔ | |
| Enable/Disable Driver | ✔ | ✔ | ✔ | ✔ | |
| Set Posture | ✔ | ✔ | ✔ | ✔ | ✔ |
| Control Movement & Velocity | ✔ | ✔ | ✔ | ✔ | ✔ |
| Adjust Standing Height | ✔ | ✔ | ✔ | ✔ | ✔ |
| Set Gait | ✔ | ✔ | ✔ | ✔ | ✔ |
| Demo Mode Control | ✔ | ✔ | ✔ | ✔ | |
| Adjust Running Speed | ✔ | ✔ | ✔ | ✔ | |
| Software Emergency Stop | ✔ | ✔ | ✔ | ✔ | |
| Resume from Emergency Stop | ✔ | ✔ | ✔ | ✔ | |
| Set Control Mode | ✔ | ✔ | ✔ | ✔ | ✔ |
| Set Client Command Source | ✔ | ✔ | ✔ | ||
| Obstacle Avoidance Switch | ✔ | ✔ | ✔ | ✔ |
Initialization
C++ Interface
explicit SDK(const std::string &server_address = "192.168.144.103:50051")
Function Description
Constructor that connects to the robot service at the specified address.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
server_address | std::string | "192.168.144.103:50051" | Server address in the format "IP:Port". |
Return Value
| Type | Description |
|---|---|
SDK | SDK instance. |
Python Interface
RobotClient(host='192.168.144.103', port=50051)
Function Description
Initialize connection to the robot.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
host | str | '192.168.144.103' | IP address of the robot host. |
port | int | 50051 | Port of the robot host. |
Return Value
| Type | Description |
|---|---|
RobotClient | RobotClient instance. |
C# Interface
void InitialRobot(RobotType robotType, IConnectionStateListener connectionStateListener = null, IPerceptionConnectionStateListener perceptionConnectionStateListener = null)
Function Description
Initialize robot connection (no need to set IP and port).
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
robotType | RobotType | Required | Type of robot. RobotType.IS: Hexapod robot, RobotType.MC: Wheeled-legged robot. |
connectionStateListener | IConnectionStateListener | null | Callback for motion connection state. |
perceptionConnectionStateListener | IPerceptionConnectionStateListener | null | Callback for perception connection state. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
void InitialRobot(RobotType robotType, string motionHostIP, string motionHostPort, string perceptionHostIP = null, string perceptionHostPort = null, IConnectionStateListener connectionStateListener = null, IPerceptionConnectionStateListener perceptionConnectionStateListener = null)
Function Description
Initialize robot connection (custom IP and port).
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
robotType | RobotType | Required | Type of robot. |
motionHostIP | string | Required | IP address of SYSA (motion module). |
motionHostPort | string | Required | Port of SYSA (motion module). |
perceptionHostIP | string | null | IP address of SYSB (perception module). |
perceptionHostPort | string | null | Port of SYSB (perception module). |
connectionStateListener | IConnectionStateListener | null | Callback for motion connection state. |
perceptionConnectionStateListener | IPerceptionConnectionStateListener | null | Callback for perception connection state. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
// Create SDK Manager
_robotSDKManager = RobotSDKManager.Instance;
// Use default address
_robotSDKManager?.InitialRobot(RobotType.IS, this, this);
// Set address manually
_robotSDKManager?.InitialRobot(RobotType.IS, "192.168.144.103", null, "192.168.144.105", null, this, this);Java Interface
HighLevelSportClient(IRobotAdapter adapter)
Function Description
Initialize robot control client and establish connection with the robot.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
adapter | IRobotAdapter | Required | Robot adapter instance. |
Return Value
| Type | Description |
|---|---|
HighLevelSportClient | Client instance. |
Example
RobotSDKManager sdkManager = RobotSDKManager.getInstance();
IRobotAdapter adapter = sdkManager.createRobotAdapter(RobotType.HEXAPOD);
HighLevelSportClient highLevelClient = new HighLevelSportClient(adapter);Enable/Disable Drive
C++ Interface
bool enableDriver(bool enable)
Function Description
Enable or disable the driver.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
enable | bool | Required | Whether to enable the driver. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
bool enable = true;
bool success = sport.enableDriver(enable);
if (success) {
std::cout << "Driver Enable Command Successful." << std::endl;
} else {
std::cout << "Failed to Enable Driver." << std::endl;
}Python Interface
driver_enable(enable=True, source=2)
Function Description
Enable/Disable the driver.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
enable | bool | True | Enable/disable the driver. |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Enable the robot driver
success = client.driver_enable(True)C# Interface
void EnableRobot()
Function Description
Enable the robot driver.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
| - | - | - | No parameters. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
void DisableRobot()
Function Description
Disable the robot driver.
Java Interface
void EnableRobot(boolean enable)
Function Description
Enable or disable the robot driver. The driver must be enabled before controlling robot movement or actions.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
enable | boolean | Required | Whether to enable the driver (true: Enable, false: Disable). |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.EnableRobot(true);Return Value
| Type | Description |
|---|---|
void | No return value. |
Notes
- The robot driver must be enabled before controlling robot movement or executing any other actions.
- The driver status can be monitored via the
MotionStatelistener. For detailed usage, refer to the Motion Status Service Interface section.
Set Robot Posture
C++ Interface
bool lieDownOrStandUp(bool lieDown)
Function Description
Control the robot to lie down or stand up.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
lieDown | bool | Required | true to stand up, false to lie down. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
bool enable = true;
bool success = sport.lieDownOrStandUp(enable);
if (success) {
std::cout << "Lie Down Or Stand Up Command Successful." << std::endl;
} else {
std::cout << "Failed to Lie Down Or Stand Up." << std::endl;
}ROS2 Interface
This interface is used to subscribe to the ROS2 /cmd_vel topic to receive robot motion velocity commands.
| Service Name | Service Type | Role |
|---|---|---|
/nav/robot_command | ysc_robot_msgs/srv/RobotCommand | Client |
Message Structure
ysc_robot_msgs/srv/RobotCommand contains the following field:
| Field Name | Type | Description |
|---|---|---|
| RobotCommand | string | A string indicating the specific command. |
Test Method
Call this interface once to toggle between standing up and lying down states.
ros2 service call /nav/robot_command ysc_robot_msgs/srv/RobotCommand "comamnd_name: 'StandUpDown'"Python Interface
lie_down_or_stand_up(state, source=2)
Function Description
Controls whether the robot lies down or stands up.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
state | bool | Required | True for standing up, False for lying down. |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
success = client.driver_enable(True) # Enable the driver
success = client.lie_down_or_stand_up(True) # Stand upNote: You must call driver_enable(True) to enable the driver before making the robot stand up.
Java Interface
void SetPostureType(boolean up)
Function Description
Control the robot to lie down or stand up.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
up | boolean | Required | true: Stand up, false: Lie down. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetPostureType(true);
C# Interface
void SetPostureType(RobotPostureType type)
Function Description
Set the robot's posture.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
type | RobotPostureType | Required | Posture type. RobotPostureType.Lie_Down: Lie down, RobotPostureType.Stand_Up: Stand up. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Notes
- The posture switching status and current posture can be obtained by monitoring
MotionState - For detailed usage, please refer to the "Motion Status Service Interface" section.
Control Movement Direction and Speed
C++ Interface
bool move(float x, float y, float yaw)
Function Description
Directional Movement Control. Controls the robot's motion in three degrees of freedom: forward/backward, left/right, and rotation.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
x | float | Required | Speed in forward/backward direction. Range depends on gait and terrain (see below). Positive = forward, negative = backward. |
y | float | Required | Speed in left/right direction. Range depends on gait and terrain (see below). Positive = left, negative = right. |
yaw | float | Required | Rotational speed. Range depends on gait and terrain (see below). Positive = counterclockwise, negative = clockwise. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
WARNING
Parameter Range and Direction Explanation:
- Normal Gait:
- Flat Terrain: x: [-1.0, 2.0], y: [-0.4, 0.4], yaw: [-0.8, 0.8]
- Slope: x: [-0.8, 0.8], y: [-0.4, 0.4], yaw: [-0.6, 0.6]
- RL Gait (All terrains including flat/slope):
- x: [-2.0, 2.0], y: [-0.4, 0.4], yaw: [-0.8, 0.8]
- Units: x, y in m/s; yaw in rad/s (approximate)
- Parameter signs indicate movement directions:
- x > 0: move forward, x < 0: move backward
- y > 0: move left, y < 0: move right
- yaw > 0: rotate counterclockwise, yaw < 0: rotate clockwise
- The absolute value of the parameter indicates speed magnitude: |x|, |y|, |yaw| → higher = faster
Actual Speed Calculation Formula:
The final movement speed is determined by three factors:
- maxSpeed: Maximum hardware speed (m/s), obtainable via
setStatusCallback - percent: Speed coefficient set via
adjustSpeedfunction (0–100) - Input values: x, y, yaw parameters provided in this function
Speed calculations:
- Actual speed in X = x × maxSpeed × percent / 100 (m/s)
- Actual speed in Y = y × maxSpeed × percent / 100 (m/s)
- Actual rotation speed = yaw × maxSpeed × percent / 100 (rad/s)
⚠️Critical Safety Mechanism: Continuous Invocation Required
- Must be called continuously: Movement will only persist if
move()is called repeatedly — a built-in safety mechanism - Auto-stop on timeout: If the backend does not receive a new
move()command within 200ms, all speed components will be set to zero - Real-time control: To maintain motion, this function should be called at >5Hz (recommend 10–20Hz)
- Failsafe design: This mechanism ensures the robot stops if communication is lost or the program crashes
Example
#include <iostream>
#include <thread>
#include <chrono>
#include "Lenovo/Daystar/SDK.h"
Lenovo::Daystar::SDK sdk;
// Attempt to connect to the SDK server with default settings
if (!sdk.isConnected()) {
std::cerr << "Cannot connect to SDK server with default settings" << std::endl;
return 1;
} else {
std::cout << "Successfully connected with default settings" << std::endl;
}
// Retrieve the sport (motion control) interface
auto &sport = sdk.getSport();
// Flag to control movement loop
bool need_to_move = true;
// Continuously send motion commands to keep the robot moving forward
while (need_to_move) {
sport.move(0.5f, 0.0f, 0.0f); // Move forward at 50% speed
std::this_thread::sleep_for(std::chrono::milliseconds(50)); // 20Hz frequency
}Note:
For a complete example, please refer to the "Creating an Application" section in the Application Development module.
Python Interface
direction_movement(linear_x=0.0, linear_y=0.0, angular_z=0.0, source=2)
Function Description
Control robot movement.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
linear_x | float | 0.0 | Forward/backward speed. Range depends on gait and terrain (see below). |
linear_y | float | 0.0 | Left/right movement speed. Range depends on gait and terrain (see below). |
angular_z | float | 0.0 | Rotational speed. Range depends on gait and terrain (see below). |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Parameter Range Explanation:
- Normal Gait:
- Flat Terrain: linear_x: [-1.0, 2.0] m/s, linear_y: [-0.4, 0.4] m/s, angular_z: [-0.8, 0.8] rad/s
- Slope: linear_x: [-0.8, 0.8] m/s, linear_y: [-0.4, 0.4] m/s, angular_z: [-0.6, 0.6] rad/s
- RL Gait (All terrains including flat/slope):
- linear_x: [-2.0, 2.0] m/s, linear_y: [-0.4, 0.4] m/s, angular_z: [-0.8, 0.8] rad/s
Example
from daystar_sdk.client import RobotClient
# Initialize client
with RobotClient(host='localhost', port=50051) as client:
# Robot movement
success = client.direction_movement(linear_x=0.5)ROS2 Interface
This interface is used to subscribe to the ROS2 /cmd_vel topic to receive velocity commands for robot movement.
| Topic Name | Topic Type | Role |
|---|---|---|
/cmd_vel | geometry_msgs::msg::Twist | Subscriber |
Message Structure
The geometry_msgs::msg::Twist message includes the following fields:
| Field Name | Type | Description |
|---|---|---|
| linear | Vector3 | Contains x, y, z representing linear velocities. |
| angular | Vector3 | Contains x, y, z representing angular velocities. |
Parameter Range Explanation:
- Normal Gait:
- Flat Terrain: linear.x: [-1.0, 2.0] m/s, linear.y: [-0.4, 0.4] m/s, angular.z: [-0.8, 0.8] rad/s
- Slope: linear.x: [-0.8, 0.8] m/s, linear.y: [-0.4, 0.4] m/s, angular.z: [-0.6, 0.6] rad/s
- RL Gait (All terrains including flat/slope):
- linear.x: [-2.0, 2.0] m/s, linear.y: [-0.4, 0.4] m/s, angular.z: [-0.8, 0.8] rad/s
Sample Message
geometry_msgs::msg::Twist twist_msg;
twist_msg.linear.x = 0.1;
twist_msg.linear.y = 0.0;
twist_msg.linear.z = 0.0;
twist_msg.angular.x = 0.0;
twist_msg.angular.y = 0.0;
twist_msg.angular.z = 0.0;Test Method
- Publish a one-time message
Use the following command to publish a one-time message to the/cmd_veltopic:
ros2 topic pub --once /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.1, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"- Continuously publish messages
Use the following command to continuously publish messages to the/cmd_veltopic at a rate of 10 times per second:
ros2 topic pub --rate 10 /cmd_vel geometry_msgs/msg/Twist "{linear: {x: 0.2, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}"Notes
● Ensure that the ROS2 node has been started and is subscribing to the /cmd_vel topic.
● The format of the published message must strictly conform to the definition of the geometry_msgs::msg::Twist message type.
● When continuously publishing messages, be sure to control the publishing frequency to avoid network congestion.
C# Interface
void MoveRobot(float[] moveDirection)
Description
Control robot movement.
Parameters
| Parameter | Type | Required/Default | Description |
|---|---|---|---|
moveDirection | float[] | Required | Movement and rotation parameters. moveDirection[0]: Velocity component in the forward/backward direction, positive for forward, negative for backward. moveDirection[1]: Velocity component in the left/right direction, positive for left, negative for right. moveDirection[2]: Rotational velocity component, positive for counterclockwise, negative for clockwise. Ranges depend on gait and terrain (see below). |
Returns
| Type | Description |
|---|---|
void | No return value. |
Parameter Range Explanation:
- Normal Gait:
- Flat Terrain: moveDirection[0]: [-1.0, 2.0] m/s, moveDirection[1]: [-0.4, 0.4] m/s, moveDirection[2]: [-0.8, 0.8] rad/s
- Slope: moveDirection[0]: [-0.8, 0.8] m/s, moveDirection[1]: [-0.4, 0.4] m/s, moveDirection[2]: [-0.6, 0.6] rad/s
- RL Gait (All terrains including flat/slope):
- moveDirection[0]: [-2.0, 2.0] m/s, moveDirection[1]: [-0.4, 0.4] m/s, moveDirection[2]: [-0.8, 0.8] rad/s
Notes
- Must be called continuously: To maintain movement, the robot requires continuous
movecommands (interval < 200ms); otherwise, it will automatically stop. - Recommendation: Call this function at a frequency of 10–20 Hz to ensure smooth motion control.
- Stopping movement: Set all movement and rotation velocities to zero:
MoveRobot(new float[] { 0, 0, 0 }).
Adjust Standing Height
Note: Currently, only IS robots support height adjustment. MC/MX robots do not support height adjustment yet.
C++ Interface
bool adjustBodyHeight(int percent)
Function Description
Adjust the robot body height.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
percent | int | Required | Height percentage, range: 20–50. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
bool success = sport.adjustBodyHeight(30);
if (success) {
std::cout << "Adjust Body Height Successful." << std::endl;
} else {
std::cout << "Failed to Adjust Body Height." << std::endl;
}Notes
- Ensure that the operation mode and the height adjustment ratio
height_adjustmentare integers within the range of 0 to 100.
Python Interface
body_height_adjust(percent, source=2)
Function Description
Adjust the robot's body height.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
percent | int | Required | Body height percentage (25–50); for IS model, the maximum is 41 and the default is 34. |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Adjust the robot's body height
success = client.body_height_adjust(50)ROS2 Interface
This service is used to adjust the robot's body height.
| Service Name | Service Type | Role |
|---|---|---|
/saturn/rc_height_scale | saturn_msgs::srv::HeightScale | Client |
Request Message
The saturn_msgs::srv::HeightScale::Request message contains the following field:
| Field Name | Type | Description |
|---|---|---|
scale | int | Integer type, representing the height scale. |
Example Message
saturn_msgs::srv::HeightScale::Request request;
request.scale = 8;
saturn_msgs::srv::HeightScale::Response response;Test Method
ros2 service call /saturn/rc_height_scale saturn_msgs/srv/HeightScale "{scale: 8}"C# Interface
void SetRobotHeight(int heightPercent)
Function Description
Control the robot's height.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
heightPercent | int | Required | Height percentage, range 20–50. Robot height range: 0.2m–0.5m. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Java Interface
void SetRobotHeight(int heightPercent)
Function Description
Control the robot's height.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
heightPercent | int | Required | Height percentage, range 20–50. Robot height range: 0.2m–0.5m. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetRobotHeight(30);Set Gait
Note:
- MC/MX type robots currently only support reinforcement learning and crawling gait.
- Gait can only be set when the robot is in a standing posture.
C++ Interface
bool setScene(SceneType sceneType)
Function Description
Set the robot's locomotion gait.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
sceneType | SceneType | Required | Gait type, defined by the SceneType enum.SceneType.WALKING: Walking gaitSceneType.STAIRS: Stair gaitSceneType.ROUGH: Slope gaitSceneType.RL_WALK: Reinforcement learning gait |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
SceneType sceneType = SceneType.WALKING;
bool success = sport.setScene(sceneType);
if (success) {
std::cout << "Adjust Body Height Successful." << std::endl;
} else {
std::cout << "Failed to Adjust Body Height." << std::endl;
}Python Interface
set_scene(scene_type, source=2)
Function Description
Set the robot's scene.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
scene_type | int | Required | Scene type. 2: Walking gait, 3: Stair gait, 8: Slope gait, 9: Reinforcement learning gait, 14: Crawing gait. |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Note
Before calling this function, you must first call driver_enable(True) to enable the driver and then call lie_down_or_stand_up(True) to make the robot stand up.
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Set the robot's movement gait
success = client.set_scene(1)ROS2 Interface
This service is used to adjust the robot's movement gait.
| Service Name | Service Type | Role |
|---|---|---|
/saturn/robot_command | ysc_robot_msgs::srv::RobotCommand | Client |
Request Message
The ysc_robot_msgs::srv::RobotCommand::Request message type contains the following field:
| Field Name | Type | Description |
|---|---|---|
command_name | string | Represents the specific command. |
Example Message
saturn_msgs::srv::HeightScale::Request request;
request.scale = "StairsGait"; //Stair gait
saturn_msgs::srv::HeightScale::Response response;Test Method
ros2 service call /saturn/robot_command ysc_robot_msgs/srv/Robot_Command "{command_name: 'StairsGait'}"C# Interface
void SetRobotScene(RobotSceneType robotSceneType)
Function Description
Set the robot's movement gait.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
robotSceneType | RobotSceneType | Required | Gait type, using the RobotSceneType enumeration. RobotSceneType.Walking: Walking gait, RobotSceneType.Stairs: Stair gait, RobotSceneType.Slope: Slope gait, RobotSceneType.RlWalk: Reinforcement learning gait, RobotSceneType.Car_Mode: Crawing gait。 |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Notes
- The gait switching status and current gait can be obtained by monitoring
MotionState. For detailed usage, refer to the "Motion Status Service Interface" section. - The robot must be in a standing posture before setting the gait; otherwise, the operation will fail.
Java Interface
void SetRobotScene(SceneType scene)
Function Description
Set the robot's movement gait.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
scene | SceneType | Required | Gait type. SceneType.Walking: Walking gait, SceneType.Stairs: Stair gait, SceneType.Slope: Slope gait. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetRobotScene(SceneType.Walking);Demo Mode Control
C++ Interface
bool demoControl(int demoType, bool enable = true)
Function Description
Demo Control.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
demoType | int | Required | Demo type: 2 (head shake), 3 (tail wag), 4 (wave). |
enable | bool | true | Whether to enable. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
int demoType = 2; // Example value: head shake
bool enable_demo = true; // Example value: enable demo mode
bool success = sport.demoControl(demoType, enable_demo);
if (success) {
std::cout << "Demo Mode Control Set Successfully." << std::endl;
} else {
std::cout << "Failed to Set Demo Mode Control." << std::endl;
}Notes
- Ensure that the provided
demoTypeandenablestatus are valid.
Python Interface
demo_control(mode, enable, source=2)
Function Description
Demo control.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
mode | int | Required | Demo mode: 2 (head shake), 3 (tail wag), 4 (wave). |
enable | bool | Required | Whether to enable the demo mode. |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Trigger demo mode: head shake
success = client.demo_control(2, True)Java Interface
void SetDemoControl(DemoType playType)
Function Description
Demo control.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
playType | DemoType | Required | Type of demo action. DemoType.SAY_HELLO: Waving, DemoType.SHAKE_HAND: Head shaking, DemoType.FISHTAILING: Tail wagging. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetDemoControl(DemoType.SAY_HELLO);C# Interface
void SetPlaybackRoutine(BionicActionType playType)
Function Description
Demo control.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
playType | BionicActionType | Required | Type of demo action. BionicActionType.SAY_HELLO: Waving, BionicActionType.SHAKE_HAND: Head shaking, BionicActionType.FISHTAILING: Tail wagging. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Adjust Running Speed
C++ Interface
bool adjustSpeed(int percent)
Function Description
Adjust speed scaling factor. Sets the robot's movement speed scaling factor, which affects the actual execution speed of all motion commands.
Speed Calculation Formula:
The final movement speed is determined by:Actual Speed = move() parameter × maxSpeed × (percent / 100)
Where:
move() parameter: Velocity components in the range [-1.0, 1.0] passed viamove(x, y, yaw)maxSpeed: The robot’s configured maximum speed (in m/s), retrievable viasetStatusCallbackpercent: Speed percentage set by this function [0, 100]
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
percent | int | Required | Speed percentage, valid range: 0–100. 0: Stops all motion, 50: Uses 50% of max speed, 100: Uses 100% of max speed. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation succeeded. |
Example
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();
bool success = sport.adjustSpeed(70);
if (success) {
std::cout << "Adjust Speed Successfully." << std::endl;
} else {
std::cout << "Failed to Adjust Speed." << std::endl;
}Notes
- It is recommended to set an appropriate speed scaling factor before motion, especially using lower speeds during testing.
- Make sure the percentage is within the range of 0–100; values outside this range may cause unexpected behavior.
Python Interface
bool speed_adjust(percent, source=2)
Function Description
Adjusts the robot's speed.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
percent | int | Required | Speed percentage (0–100). |
source | int | 2 | Control mode (1: Navigation Mode, 2: Joystick Mode). |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Adjust robot speed
success = client.speed_adjust(62)C# Interface
void SetRobotSpeed(int speedPercent)
Function Description
Adjust speed scaling factor. Sets the robot’s motion speed scaling factor, affecting the actual execution speed of all movement commands.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
speedPercent | int | Required | Speed percentage (0–100). |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Notes:
- It is recommended to set a proper speed factor before moving the robot, especially using a lower speed during testing.
- Ensure the
speedPercentis within the 0–100 range. Exceeding this may cause unexpected behavior. - To obtain the robot’s maximum and current speed, refer to the Motion Status Service Interface section.
Java Interface
void SetRobotSpeed(int speedPercent)
Function Description
Sets the robot’s motion speed scaling factor.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
speedPercent | int | Required | Speed percentage (0–100). |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetRobotSpeed(50);Software Emergency Stop
C++ Interface
bool emergencyStop()
Function Description
Software Emergency Stop.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
bool success = sport.emergencyStop();
if (success) {
std::cout << "Emergency Stop Successfully." << std::endl;
} else {
std::cout << "Failed to Emergency Stop." << std::endl;
}Python Interface
driver_estop()
Function Description
Emergency stop for the driver.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize client
with RobotClient(host='localhost', port=50051) as client:
# Trigger emergency stop
success = client.driver_estop()Java Interface
void SetDriverEStop()
Function Description
Software Emergency Stop.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetDriverEStop();C# Interface
void SetDriverEStop()
Function Description
Software Emergency Stop.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
void | No return value. |
Notes
- After triggering the robot's emergency stop, you must reset the software emergency stop before the robot can be re-enabled and controlled to stand.
- To obtain the robot's emergency stop status, please refer in detail to the "Motion Status Service Interface" section.
Resume from software emergency stop
C++ Interface
bool resumeFromEmergencyStop()
Function Description
Resume from software emergency stop.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
bool success = sport.resumeFromEmergencyStop();
if (success) {
std::cout << "Resume From Emergency Stop Successfully." << std::endl;
} else {
std::cout << "Failed to Resume From Emergency Stop." << std::endl;
}Python Interface
resume_estop()
Function Description
Resume from software emergency stop.
Parameter Description
Java Interface
void SetResumeEStop()
Function Description
Resume from software emergency stop.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetResumeEStop();None.
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Resume robot from software emergency stop
success = client.resume_estop()C# Interface
void SetResumeEStop()
Function Description
Resume from software emergency stop.
Parameter Description
None.
Return Value
| Type | Description |
|---|---|
void | No return value. |
Set Control Mode
This service sets the robot's control mode, switching between manual or navigation mode.
C++ Interface
bool setControlMode(Lenovo::Daystar::ControllerMode controllerMode)
Function Description
Set control mode to navigation, joystick, or UWB.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
controllerMode | Lenovo::Daystar::ControllerMode | Required | Control mode, using Lenovo::Daystar::ControllerMode enumeration. NAV_CONTROL: Navigation control mode, JOY_CONTROL: Joystick control mode, UWB_CONTROL: UWB control mode. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
Lenovo::Daystar::ControllerMode controllerMode = Lenovo::Daystar::ControllerMode.NAV_CONTROL;
bool success = sport.setControlMode(controllerMode);
if (success) {
std::cout << "Set Control Mode Successful." << std::endl;
} else {
std::cout << "Failed to Set Control Mode." << std::endl;
}Notes
- Ensure that the control mode provided is valid.
- Set the robot pose.
Python Interface
set_nav_or_joy_control(nav_or_joy)
Function Description
Set navigation or joystick control mode.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
nav_or_joy | int | Required | Control mode. 1: Navigation Mode, 2: Joystick Mode. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Set the robot to navigation control mode
success = client.set_nav_or_joy_control(1)ROS2 Interface
| Service Name | Service Type | Role |
|---|---|---|
/saturn/robot_command | ysc_robot_msgs::srv::RobotCommand | Client |
Request Message
The message type ysc_robot_msgs::srv::RobotCommand::Request contains the following field:
| Field Name | Type | Description |
|---|---|---|
command_name | string | Specifies the command to execute. "EnableNavigation": Enables navigation mode "EnableTeleoption": Enables joystick control mode |
Example Message
saturn_msgs::srv::HeightScale::Request request;
request.scale = "EnableNavigation"; //navigation mode
saturn_msgs::srv::HeightScale::Response response;Test Method
ros2 service call /saturn/rc_nav_or_manual saturn_msgs/srv/NavOrManual "{command_name: 'EnableNavigation'}"C# Interface
void SwitchRobotControlMode(RobotControlType controlType)
Function Description
Set the robot control mode.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
controlType | RobotControlType | Required | Control type. RobotControlType.Joy_Mode: Remote control mode, RobotControlType.Nav_Mode: Navigation mode, RobotControlType.Follow_Mode: Follow mode. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Notes
- When using manual control, set the mode to Remote Control Mode (Joy_Mode).
- To get the current control mode, please refer to the "Motion State Service Interface" section for details.
Java Interface
void SetControlMode(ControlMode mode)
Function Description
Set the robot control mode.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
mode | ControlMode | Required | Control type. ControlMode.JOY_CONTROL: Remote control mode, ControlMode.NAV_CONTROL: Navigation mode. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetControlMode(ControlMode.JOY_CONTROL);Set Client Command Source
C# Interface
void SetClientCommandSource(RobotControlType controlSource)
Function Description
Set the client command source.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
controlSource | RobotControlType | Required | RobotControlType.Nav_Mode: Navigation mode, RobotControlType.Joy_Mode: Remote control mode (default). |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Java Interface
void SetClientCommandSource(ControlMode mode)
Function Description
Set the client command source.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
mode | ControlMode | Required | ControlMode.NAV_CONTROL: Navigation mode, ControlMode.JOY_CONTROL: Remote control mode (default). |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetClientCommandSource(ControlMode.NAV_CONTROL);Set the Obstacle Avoidance Switch
C++ Interface
bool setGuardianSwitch(bool enable)
Function Description
Set the Obstacle Avoidance Switch.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
enable | bool | Required | true to enable obstacle avoidance, false to disable. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
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();
Lenovo::Daystar::ControllerMode controllerMode = Lenovo::Daystar::ControllerMode.NAV_CONTROL;
bool success = sport.setGuardianSwitch(true);;
if (success) {
std::cout << "Set Control Mode Successful." << std::endl;
} else {
std::cout << "Failed to Set Control Mode." << std::endl;
}Python Interface
set_guardian_switch(guardian)
Function Description
Set obstacle avoidance (guardian) switch.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
guardian | bool | Required | True: Enable obstacle avoidance, False: Disable obstacle avoidance. |
Return Value
| Type | Description |
|---|---|
bool | Whether the operation was successful. |
Example
from daystar_sdk.client import RobotClient
# Initialize the client
with RobotClient(host='192.168.144.105', port=50051) as client:
# Enable the obstacle avoidance function
success = client.set_guardian_switch(True)C# Interface
void SetAvoidObstacle(bool enable)
Function Description
Set the obstacle avoidance switch.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
enable | bool | Required | true to enable obstacle avoidance, false to disable it. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Note
- To retrieve the status of obstacle avoidance, please refer to the "Motion Status Service Interface" section for detailed usage instructions.
Java Interface
void SetAvoidObstacle(boolean enable)
Function Description
Set the obstacle avoidance switch.
Parameter Description
| Parameter Name | Type | Required/Default | Description |
|---|---|---|---|
enable | boolean | Required | true to enable obstacle avoidance, false to disable it. |
Return Value
| Type | Description |
|---|---|
void | No return value. |
Example
highLevelClient.SetAvoidObstacle(true);