Skip to content

Robotic Arm Joint Angle Pass-through Demo

1. Project introduction

This project demonstrates how to pass through the pre-planned joint angle points to the robotic arm and, during the arm's motion, receive and process the state data actively reported by the robotic arm via UDP through a callback function. It is built with CMake and utilizes the C language development package for the robotic arm provided by RealMan.

2. Code structure

RMDemo_MovejCANFD
├── build              # Output directory generated by CMake build (Makefile, build file, etc.)
├── data               # Pass-through trajectory file available of different models of robotic arms
│   ├── RM65&RM63_canfd_data.txt    
│   ├── ECO65_canfd_data.txt
│   └── ...
├── include              # Custom header file storage directory
├── Robotic_Arm          # RealMan robotic arm secondary development package
│   ├── include
│   │   ├── rm_define.h  # Header file of the robotic arm secondary development package, containing defined data types and structures
│   │   └── rm_interface.h # Header file of the robotic arm secondary development package, declaring all operation interfaces of the robotic arm口
│   └── lib
│       ├── api_c.dll    # API library for Windows 64bit
│       ├── api_c.lib    # API library for Windows 64bit
│       └── libapi_c.so  # API library for Linux x86
├── src
│   └── main.c           # Main function
├── CMakeLists.txt       # Top-level CMake configuration file of the project
├── readme.md            # Project description document
├── run.bat              # Windows quick run script
└── run.sh               # linux quick run script

3. Project download

Download RM_API2 locally via the link: development package download. Then, navigate to the RM_API2\Demo\RMDemo_C directory, where you will find RMDemo_MovejCANFD.

4. Environment configuration

Required environment and dependencies for running in Windows and Linux environments:

ItemLinuxWindows
System architecturex86 architecture-
CompilerGCC 7.5 or higherMSVC2015 or higher 64bit
CMake version3.10 or higher3.10 or higher
Specific dependencyRMAPI Linux version library (located in the Robotic_Arm/lib directory)RMAPI Windows version library (located in the Robotic_Arm/libdirectory)

Linux configuration

1. Compiler (GCC) In most Linux distributions, GCC is installed by default, but the version may not be the latest. If a specific version of GCC (such as 7.5 or higher) is required, it can be installed via the package manager. For example, on Ubuntu, you can use the following commands to install or update GCC:

bash
# Check GCC version
gcc --version

sudo apt update
sudo apt install gcc-7 g++-7

Note: If the GCC version installed by default on the system meets or exceeds the required version, no additional installation is necessary.

2. CMake CMake can also be installed through the package manager in most Linux distributions. For example, on Ubuntu:

bash
sudo apt update
sudo apt install cmake

# Check CMake version
cmake --version

Windows configuration

  • Compiler (MSVC2015 or higher): The MSVC (Microsoft Visual C++) compiler is typically installed with Visual Studio. You can install it by following these steps:

    1. Visit the Visual Studio official website to download and install Visual Studio.
    2. During installation, select the "Desktop development with C++" workload, which will include the MSVC compiler.
    3. Select additional components as needed, such as CMake (if not already installed).
    4. After installation, open the Visual Studio command prompt (available in the start menu) and enter the cl command to check if the MSVC compiler is installed successfully.
  • CMake: If CMake was not included during the Visual Studio installation, you can download and install CMake separately.

    1. Visit the CMake official website to download the installer for Windows.
    2. Run the installer and follow the on-screen instructions to complete the installation.
    3. After installation, add the CMake bin directory to the system's PATH environment variable (this is typically asked during installation).
    4. Open the command prompt or PowerShell and enter cmake --version to check if CMake has been installed successfully.

5. User guide

5.1. Quick run

Follow these steps to quickly run the code:

  1. Configuration of the IP address of the robotic arm: Open the main.c file and modify the parameters of the robot_ip_address in the main function to the current IP address of the robotic arm. The default IP address is "192.168.1.18".

    C
    const char *robot_ip_address = "192.168.1.18";
    
    int robot_port = 8080;
    rm_robot_handle *robot_handle = rm_create_robot_arm(robot_ip_address, robot_port);
  2. Running via linux command line: Navigate to the RMDemo_MovejCANFD directory in the terminal, and enter the following command to run the C program:

    bash
    chmod +x run.sh
    ./run.sh

    The running result is as follows:

  3. Running on Windows: double-click the run.bat script to run The running result is as follows:

5.2 Description of key codes

The following are the main functions of the main.c:

  • Connect the robotic arm

    C
    rm_robot_handle *robot_handle = rm_create_robot_arm(robot_ip_address, robot_port);

    Connect the robotic arm to the specified IP address and port.

  • Get the API version

    C
    char *api_version = rm_api_version();
    printf("API Version: %s.\n", api_version);

    Get and display the API version.

  • Configure real-time push

    C
    rm_realtime_push_config_t config = {5, true, 8089, 0, "192.168.1.88"};
    int result = rm_set_realtime_push(robot_handle, config);
  • Read the joint angle trajectory file and perform pass-through

    C
    demo_movej_canfd(robot_handle)
  • Disconnect from the robotic arm

    C
    disconnect_robot_arm(robot_handle);

5.3 Demo of running results

After running the script, the output result is as follows:

bash
Run...
API Version: 1.0.0.
Robot handle created successfully: 1
Joint positions:
0.02 -25.82 -38.03 -0.04 -116.15 -0.00
Joint positions:
...
Joint positions:
0.02 -25.82 -38.03 -0.03 -116.15 0.00
Joint positions:
0.02 -25.82 -38.03 -0.03 -116.15 0.00
Joint positions:
0.02 -25.82 -38.03 -0.03 -116.15 0.00
Successfully set realtime push configuration.
Trying to open file: C:/Users/realman/830/RM_API2-main/RM_API2-main/Demo/RMDemo_C/RMDemo_MovejCANFD/data/RM65&RM63_canfd_data.txt
Total points: 3600
The motion is complete, the arm is in place.
Motion result: 1
Current device: 0
Is the next trajectory connected: 0
Moving to point 0
Moving to point 3598
Moving to point 3599
Pass-through completed
The motion is complete, the arm is in place.
Motion result: 1
Current device: 0
Is the next trajectory connected: 0
movej_cmd joint movement 1: 0
Press any key to continue...

After running the script, the trajectory from top to bottom is shown in the following image:

moveCANFD

6. License information

  • This project is subject to the MIT license.