Skip to content

Creating an Application​​

This section guides users on how to create their own application using the Daystar Bot SDK.

By leveraging the mc_client_interface header file from the Daystar Bot SDK, users can develop various high-level applications. This section provides a step-by-step tutorial on using mc_client_interface to create a high-level application that commands the Daystar Robot to stand up and walk.

Review mc_client_interface API

The mc_client_interface is a header file provided by the Daystar Bot SDK. The developers can use its API to control Robot.

The file is located at:

rc_sdk/sdk/include/mc_client_interface.h

cpp
#ifndef MC_CLIENT_INTERFACE_H
#define MC_CLIENT_INTERFACE_H

#include <iostream>
#include <memory>
#include <string>
#include <vector>
#include "common.h"

using namespace robot_control;

// SDK init Interface
bool rcClientInterfaceInit(std::string target_ip);

// High-level Motion Interface
bool rcClientInterfaceDriverEnable(robot_control::common::NAV_OR_JOY_MODE from, bool driver_enable);
bool rcClientInterfaceDirectionMovement(robot_control::common::NAV_OR_JOY_MODE from, common::ROBOT_TWIST rc_direct, int64_t time_millis);
bool rcClientInterfaceBodyHighAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
bool rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE from, common::SCENE_TYPE scene);
bool rcClientInterfaceDemoControl(common::NAV_OR_JOY_MODE from, int mode, bool enable);
bool rcClientInterfaceSpeedAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale);
bool rcClientInterfaceDriverSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
bool rcClientInterfacercResumeSoftEstop(robot_control::common::NAV_OR_JOY_MODE from);
bool rcClientInterfaceSetNavOrJoyControl(common::NAV_OR_JOY_MODE nav_joy);

// Low-level Motion Interface
bool rcClientInterfaceClearDriverError(unsigned int mask);
bool rcClientInterfaceReCalibrateAllDriverAndSave(bool is_rough);
// Clear BISS error Interface
bool rcClientInterfaceZeroTorqueSensor(robot_control::common::NAV_OR_JOY_MODE from);


// Device Status Service Interface
bool rcClientInterfaceGetCommonStatus(common::ROBOT_COMMON_STATUS *com_state);
bool rcClientInterfaceGetJointsStatus(common::ROBOT_JOINTS_STATUS *state);

// Basic Service Interface
bool rcClientInterfaceGetChargeState(common::JETSON_CHARGE_STATE *charge_state);
bool rcClientInterfaceEnterOrExitCharge(robot_control::common::NAV_OR_JOY_MODE from, bool driver_enable);
bool rcClientInterfaceGetImuData(common::MC_MOTION_IMU_DATA *imu_data);
bool rcClientInterfaceGetImuStreamData(std::vector<common::MC_MOTION_IMU_DATA> *imu_data_list);

// Fault Service Interface
bool rcClientInterfaceLogUpdate(std::vector<std::string> &log_list);

// System Info Interface
std::string rcClientInterfaceGetMcVersion(const int& index);
std::string rcClientInterfaceGetRobotName(const int& index);

// Guardian Interface
bool rcClientInterfaceSetGuardian(common::NAV_OR_JOY_MODE from, float velocity_decay_ratio, std::string trigger_source);
bool rcClientInterfaceSetGuardianSwitch(robot_control::common::NAV_OR_JOY_MODE from, bool enable);

#endif // MC_CLIENT_INTERFACE_H

Based on the application described earlier, the following functions are used:

  1. bool rcClientInterfaceInit(std::string target_ip); - Initializes the SDK
  2. bool rcClientInterfaceDriverEnable(robot_control::common::NAV_OR_JOY_MODE from, bool driver_enable); - Enable
  3. bool rcClientInterfaceSetScene(robot_control::common::NAV_OR_JOY_MODE from, common::SCENE_TYPE scene); - Sets robot scene mode(navi/joystick)
  4. bool rcClientInterfaceSpeedAdjust(robot_control::common::NAV_OR_JOY_MODE from, int scale); - Adjusts robot movement speed coefficient
  5. bool rcClientInterfaceGetCommonStatus(common::ROBOT_COMMON_STATUS *com_state); -** Reads robot status**
  6. rcClientInterfaceDirectionMovement(robot_control::common::NAV_OR_JOY_MODE from, common::ROBOT_TWIST rc_direct, int64_t time_millis); - Controls robot movement

Creating Application Files

Next, create your application project with SDK.

The following instructions assume the working directory is:
/home/daystar/sdk_test_project

Execute the following commands sequentially:

  1. Copy the SDK .so library files and .h header files to the corresponding directories in your application project (select either the ARM or x86 SDK .so files based on your development platform).
  2. Create an app_test.cpp file.
  3. Write code to call the SDK interfaces and implement your application logic.
bash
cd /home/daystar/sdk_test_project
mkdir include src libs
cp /sdk/include/* include/
cp /sdk/lib/arm/* libs/
cd src
touch app_test.cpp

Let's edit app_test.cpp!

  1. include header file:
plain
#include "include/mc_client_interface.h"
  1. Implementing Application Logic with SDK
cpp
// Init
rcClientInterfaceInit("192.168.100.103");
common::NAV_OR_JOY_MODE mode = common::NAV_OR_JOY_MODE::joy_control;
// Enable
rcClientInterfaceDriverEnable(mode, true);
// Set Walking Gait
common::SCENE_TYPE scene = common::WALKING;
rcClientInterfaceSetScene(mode, scene);
// Set Maximum Walking Speed Coefficient (1-100)
float max_speed_factor = 1;  
rcClientInterfaceSpeedAdjust(mode, max_speed_factor);
// Get Robot Status
common::ROBOT_COMMON_STATUS status;
rcClientInterfaceGetCommonStatus(&status);
// Walk Forward at 0.5 m/s
common::ROBOT_TWIST direction = {{0.5, 0.0, 0.0}, {0.0, 0.0, 0.0}};
rcClientInterfaceDirectionMovement(mode, direction, status.heartbeat);

The complete code is as follows:

cpp
#include "mc_client_interface.h"
#include <unistd.h>

int main(int argc, char **argv)
{
    common::NAV_OR_JOY_MODE mode = common::NAV_OR_JOY_MODE::joy_control;
    // Init
    rcClientInterfaceInit("192.168.100.103");
    // Enable
    rcClientInterfaceDriverEnable(mode, true);

    // Set Walking Gait
    common::SCENE_TYPE scene = common::WALKING;
    rcClientInterfaceSetScene(mode, scene);
    usleep(5000000); // Wait for switching to walking gait

    // Set Maximum Walking Speed Coefficient (1-100)
    float max_speed_factor = 1; 
    rcClientInterfaceSpeedAdjust(mode, max_speed_factor);

    // Walk Forward at 0.5 m/s
    common::ROBOT_COMMON_STATUS status;
    common::ROBOT_TWIST direction = {{0.5, 0.0, 0.0}, {0.0, 0.0, 0.0}};
    int32_t count = 10;
    for (size_t i = 0; i < count; i++)
    {
        rcClientInterfaceGetCommonStatus(&status);
        rcClientInterfaceDirectionMovement(mode, direction, status.heartbeat);
        usleep(100000);
    }
    return 0;
}

1. Compile the Application Files

After completing the application logic, proceed to compile the application files.

Add the compilation commands to the sdk_test_project/CMakeLists.txt file, then save the file.

cpp
if(CMAKE_SYSTEM_PROCESSOR MATCHES "aarch64")
    set(MC_CLIENT_LIB ${CMAKE_SOURCE_DIR}/libs/arm/libmc_client.so) # for rc_sdk
elseif(CMAKE_SYSTEM_PROCESSOR MATCHES "x86_64")
    set(MC_CLIENT_LIB ${CMAKE_SOURCE_DIR}/libs/x86_64/libmc_client.so) # for rc_sdk
endif()

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

target_include_directories(app_test PRIVATE
     include
)

target_link_libraries(app_test PRIVATE ${MC_CLIENT_LIB})

Finally, compile and run.

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

Run the Application

Connect to the robot's network (e.g., IS_Plus_001), ensuring that your development device and the robot are on the same local network. Open a terminal and execute the following commands sequentially to launch the application.

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

Important Notes
This application forwards control commands to the Daystar Bot robot via the motion control service. Before running the application, ensure the robot is in normal operating condition. For details, refer to the [Daystar Bot APP] section.