Skip to content

Motion Service Interfaces

Introduction

Motion Service Interfaces:

Control the robot's stand/lie down posture, body height, gait, charging, and velocity through Python function calls.

PurposePython
Stand Up
Lie Down
Get Robot Posture State
Adjust Standing Height
Set Gait
Get Gait
Set Control Mode
Get Control Mode
Go to Charging Dock
Leave Charging Dock
Get Dock State
Get Battery State
Check Charging Status
Velocity Control

Stand and Lie Down

Python Interface

stand_up(timeout=30)

Function Description
Make the robot stand up. Intelligently checks the current posture state before sending commands:

  • Already standing: returns success immediately without sending extra commands
  • Currently in the process of standing up: returns failure (wait for completion)
  • Lying down: sends stand up command

Parameter Description

Parameter NameTypeRequired/DefaultDescription
timeoutint30Service call timeout in seconds.

Return Value

TypeDescription
StandUpResponsestate.code == 0 indicates success; response.result is a boolean indicating whether the command executed successfully.

Example

python
from daystar_api.lowlevel_skills import stand_up

result = stand_up()
if result.response.result:
    print("Robot is now standing")
else:
    print(f"Stand up failed: {result.state.describe}")

lie_down(timeout=30)

Function Description
Make the robot lie down. Intelligently checks the current posture state before sending commands:

  • Already lying down: returns success immediately without sending extra commands
  • Currently in the process of standing up: returns failure (cannot interrupt)
  • Standing: sends lie down command

Parameter Description

Parameter NameTypeRequired/DefaultDescription
timeoutint30Service call timeout in seconds.

Return Value

TypeDescription
LieDownResponsestate.code == 0 indicates success; response.result is a boolean indicating whether the command executed successfully.

Example

python
from daystar_api.lowlevel_skills import lie_down

result = lie_down()
if result.response.result:
    print("Robot is now lying down")
else:
    print(f"Lie down failed: {result.state.describe}")

get_robot_state()

Function Description
Get the robot's current posture state with automatic data validation. Returns UNKNOWN_STATE when data is stale or unavailable.

Parameter Description

No parameters.

Return Value

TypeDescription
GetRobotStateResponsestate.code == 0 indicates success; robot_state is a RobotState enum: LIE_DOWN(0) lying down, STANDING_UP(1) standing up in transition, STAND_UP(2) standing, UNKNOWN_STATE(99) unknown.

Example

python
from daystar_api.lowlevel_skills import get_robot_state, RobotState

response = get_robot_state()
if response.state.code == 0:
    if response.robot_state == RobotState.STAND_UP:
        print("Robot is standing")
    elif response.robot_state == RobotState.LIE_DOWN:
        print("Robot is lying down")

Body Control

Python Interface

adjust_body_height(percent, timeout=5)

Function Description
Adjust the robot's standing height (percentage). The robot must be standing to adjust height. Valid range is 20–50.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
percentintRequiredHeight percentage, valid range 20–50.
timeoutint5Service call timeout in seconds.

Return Value

TypeDescription
RobotCommandResponsestate.code == 0 indicates success; response.result is a boolean indicating whether the command executed successfully.

Example

python
from daystar_api.lowlevel_skills import adjust_body_height

result = adjust_body_height(30)
if result.response.result:
    print("Height adjusted to 30%")

set_gait(gait_type, timeout=5)

Function Description
Set the robot gait type. The robot must be standing to switch gait.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
gait_typeGaitTypeRequiredGait type enum. GaitType.TROT(0) normal gait; GaitType.NORMAL_STAIR(1) normal stair gait; GaitType.SENSE_STAIR(6) sensing stair gait; GaitType.POSE_ADJUST(13) pose adjustment; GaitType.CAR_MODE(14) crawl mode; GaitType.RL_TROT(0x20) RL trot; GaitType.RL_MOUNTAIN(0x21) RL mountain gait.
timeoutint5Service call timeout in seconds.

Return Value

TypeDescription
RobotCommandResponsestate.code == 0 indicates success; response.result is a boolean.

Example

python
from daystar_api.lowlevel_skills import set_gait, GaitType

result = set_gait(GaitType.TROT)
if result.response.result:
    print("Gait set to normal trot")

get_gait()

Function Description
Get the robot's current gait type with automatic data validation. Returns UNKNOWN_GAIT when data is stale or unavailable.

Parameter Description

No parameters.

Return Value

TypeDescription
GetGaitResponsestate.code == 0 indicates success; gait_type is a GaitType enum value.

Example

python
from daystar_api.lowlevel_skills import get_gait, GaitType

response = get_gait()
if response.state.code == 0:
    print(f"Current gait: {response.gait_type}")

Control Mode

Python Interface

set_control_mode(mode, timeout=5)

Function Description
Set the robot control mode, switching between manual joystick mode and automatic navigation mode.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
modeControlModeRequiredControl mode enum. ControlMode.JOY_MODE(0) joystick manual control; ControlMode.NAV_MODE(1) navigation automatic control.
timeoutint5Service call timeout in seconds.

Return Value

TypeDescription
RobotCommandResponsestate.code == 0 indicates success; response.result is a boolean.

Example

python
from daystar_api.lowlevel_skills import set_control_mode, ControlMode

# Switch to navigation mode
result = set_control_mode(ControlMode.NAV_MODE)
if result.response.result:
    print("Switched to navigation mode")

get_control_mode()

Function Description
Get the robot's current control mode with automatic data validation. Returns UNKNOWN_MODE when data is stale or unavailable.

Parameter Description

No parameters.

Return Value

TypeDescription
GetControlModeResponsestate.code == 0 indicates success; control_mode is a ControlMode enum: JOY_MODE(0) joystick mode, NAV_MODE(1) navigation mode, UNKNOWN_MODE(99) unknown.

Example

python
from daystar_api.lowlevel_skills import get_control_mode, ControlMode

response = get_control_mode()
if response.state.code == 0:
    if response.control_mode == ControlMode.NAV_MODE:
        print("Currently in navigation mode")

Charging

Python Interface

go_to_dock(timeout=60)

Function Description
Command the robot to go to the charging dock.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
timeoutint60Service call timeout in seconds.

Return Value

TypeDescription
GoToDockResponsestate.code == 0 indicates success; response.result is a boolean.

Example

python
from daystar_api.lowlevel_skills import go_to_dock

result = go_to_dock()
if result.response.result:
    print("Robot is heading to charging dock")

leave_dock(timeout=60)

Function Description
Command the robot to leave the charging dock. The robot must be on the dock to execute this command.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
timeoutint60Service call timeout in seconds.

Return Value

TypeDescription
LeaveDockResponsestate.code == 0 indicates success; response.result is a boolean.

Example

python
from daystar_api.lowlevel_skills import leave_dock

result = leave_dock()
if result.response.result:
    print("Robot is leaving the charging dock")

get_dock_state()

Function Description
Get the current charging dock state with automatic data validation. Returns UNKNOWN_DOCK when data is stale or unavailable.

Parameter Description

No parameters.

Return Value

TypeDescription
GetDockStateResponsestate.code == 0 indicates success; dock_state is a DockState enum: IDLE(0) idle, GOING_TO_DOCK(1) going to dock, LIE_ON_DOCKER(4) charging on dock, LEAVE_DOCK(7) left dock, UNKNOWN_DOCK(99) unknown.

Example

python
from daystar_api.lowlevel_skills import get_dock_state, DockState

response = get_dock_state()
if response.state.code == 0:
    if response.dock_state == DockState.LIE_ON_DOCKER:
        print("Robot is charging on dock")

Battery State

Python Interface

get_battery_state()

Function Description
Get the robot's complete battery state information with automatic data validation. is_valid is False when data is stale or unavailable.

Parameter Description

No parameters.

Return Value

TypeDescription
GetBatteryStateResponsestate.code == 0 indicates success; is_valid indicates whether the data is valid; battery_state.percentage charge percentage (0–100); battery_state.voltage voltage (V); battery_state.current current (A, negative indicates discharge); battery_state.temperature temperature (°C); battery_state.power_supply_status charging status (1=charging, 4=full).

Example

python
from daystar_api.lowlevel_skills import get_battery_state

response = get_battery_state()
if response.state.code == 0 and response.is_valid:
    battery = response.battery_state
    print(f"Battery level: {battery.percentage}%")
    print(f"Voltage: {battery.voltage}V")
    print(f"Temperature: {battery.temperature}°C")

is_charge()

Function Description
Check if the robot is currently charging with automatic data validation. Returns False when data is stale or unavailable.

Parameter Description

No parameters.

Return Value

TypeDescription
IsChargeResponsestate.code == 0 indicates success; is_charging is a boolean: True means currently charging, False means not charging (or data unavailable).

Example

python
from daystar_api.lowlevel_skills import is_charge

response = is_charge()
if response.is_charging:
    print("Robot is charging")
else:
    print("Robot is not charging")

Velocity Control

Python Interface

send_cmd_vel(linear_x=0.0, linear_y=0.0, angular_z=0.0, dt=1.0, blocking=True)

Function Description
Send velocity commands via the /cmd_vel topic to control robot movement direction and speed, supporting omnidirectional movement. Supports both blocking and non-blocking modes.

Parameter Description

Parameter NameTypeRequired/DefaultDescription
linear_xfloat0.0Forward/backward linear velocity (m/s). Positive moves forward, negative moves backward. Recommended range for normal gait on flat ground: [-1.0, 2.0].
linear_yfloat0.0Left/right lateral velocity (m/s, omnidirectional). Positive moves left, negative moves right. Recommended range: [-0.4, 0.4].
angular_zfloat0.0Angular velocity (rad/s). Positive is counter-clockwise (turn left), negative is clockwise (turn right). Recommended range: [-0.8, 0.8].
dtfloat1.0Movement duration in seconds. dt > 0 automatically stops after dt seconds; dt = 0 continues moving until a manual stop command is sent.
blockingboolTrueIf True, blocks until movement completes; if False, returns immediately and motion runs in the background.

Return Value

TypeDescription
SendCmdVelResponsestate.code == 0 indicates success; success field indicates whether the command was sent successfully.

Example

python
from daystar_api.lowlevel_skills import send_cmd_vel

# Move forward for 1 second (blocking)
result = send_cmd_vel(linear_x=0.5, dt=1.0)

# Rotate left in place (non-blocking, background execution)
result = send_cmd_vel(angular_z=0.3, dt=2.0, blocking=False)

# Move forward continuously (requires manual stop)
send_cmd_vel(linear_x=0.3, dt=0.0)
# ... perform other operations ...
send_cmd_vel()  # Send stop command