Quick Start

What Programming Tool Do You Use?

Robotic Hand Python Start Guide

This page is for Python / Modbus / Windows

NOTE: For more guidance about other environments, please ask our agent to provide it.

1 Install SDK

Note: Use Chrome browser to open this page, otherwise the text content may not display color.

# git clone repository
git clone [email protected]:BrainCoTech/stark-serialport-example.git
# TIP: 
# Since the git clone command requires setting up an SSH public key, 
# if you don't have a GitHub account or are unfamiliar with the setup, 
# you can manually download and unzip the files from GitHub.


# Download dependencies
# 1、Download dependencies using the command line. Git Bash is recommended.
[choco setup](https://docs.chocolatey.org/en-us/choco/setup) # Install chocolatey
choco install 7zip -y # Use choco to install 7zip
sh download-lib.sh # Install dependencies, execute 7zip and sh commands within Git Bash
download-lib.bat # Install dependencies

# For users who prefer a more manual approach, downloading and extracting files manually is an alternative option.

# 2、Optional: Download manually
https://app.brainco.cn/universal/stark-serialport-prebuild/v0.2.0/win.zip
https://github.com/BrainCoTech/stark-serialport-example/blob/main/dll/msvcp140_app.dll
https://github.com/BrainCoTech/stark-serialport-example/blob/main/dll/vcruntime140_app.dll
https://github.com/BrainCoTech/stark-serialport-example/blob/main/dll/vcruntime140_1_app.dll

# The directory structure is as follows:
dist
├── include
│   └── stark_sdk.h
└── win
    └── shared
        ├── msvcp140_app.dll
        ├── stark.dll
        ├── uv.dll
        ├── vcruntime140_1_app.dll
        └── vcruntime140_app.dll

cd python
# Install Python Dependencies
which python3 # View Python path
which pip3 # View pip road
python3 -V # Check Python version
pip3 install -r requirements.txt # Install Python Dependencies

2.1 Get Device Information

StarkSDK.init(isModbus=True, log_level=logging.INFO)

# Open the serial port
# Connect ModbusClient
serial_port_name = "/dev/ttyUSB0" 
client = client_connect(port=serial_port_name, baudrate=BaudRate.baudrate_115200)

# Initialize the device
slave_id = 1 # default slave_id is 1 in Modbus Firmware
device = StarkDevice.create_device(slave_id, f"{serial_port_name}_{slave_id}") 

# Set register read/write callback
device.set_write_registers_callback(lambda register_address, values: client_write_registers(client, register_address, values=values, slave=slave_id))
device.set_read_holding_registers_callback(lambda register_address, count: client_read_holding_registers(client, register_address, count, slave=slave_id))
device.set_read_input_registers_callback(lambda register_address, count: client_read_input_registers(client, register_address, count, slave=slave_id))

# Get serial port configuration
device.get_serialport_cfg(lambda cfg: SKLog.info(f"Serialport cfg: {cfg}"))
# Get device information
device.get_motorboard_info(lambda info: SKLog.info(f"Motorboard info: {info}"))

# Close ModbusClient
client_close(client)

2.2 Basic Setting

Key info:

  • Set force level: SKLog.info(f”set_force_level”)
    device.set_force_level(force_level=ForceLevel.full)
  • Force level: small/normal/full
StarkSDK.init(isModbus=True, log_level=logging.INFO)

def init_register_rw_callback(device, client, slave_id):
    # set modbus device write/read registers callbacks
    device.set_write_registers_callback(lambda register_address, values: client_write_registers(client, register_address, values=values, slave=slave_id))
    device.set_read_holding_registers_callback(lambda register_address, count: client_read_holding_registers(client, register_address, count, slave=slave_id))
    device.set_read_input_registers_callback(lambda register_address, count: client_read_input_registers(client, register_address, count, slave=slave_id))    

def create_device(client, slave_id):
    device = StarkDevice.create_device(slave_id, f"{serial_port_name}_{slave_id}")
    init_register_rw_callback(device, client, slave_id)
    return device

def test_update_slave_id(device, client, new_slave_id):
    # 1. before set_serial_device_id, get current serialport_cfg, should be old_slave_id
    device.get_serialport_cfg(lambda cfg: SKLog.info(f"serialport_cfg: {cfg}"))
    # 2. set serial device id, device will reboot after device id changed
    old_slave_id = device.slave_id
    device.set_serial_device_id(new_slave_id)
    # 3. re-create device and set modbus client read/write registers callbacks
    device = create_device(client, new_slave_id)
    # 4. wait 3s for device reboot
    time.sleep(3)
    # 5. get new device id, should be new_slave_id
    device.get_serialport_cfg(lambda cfg: SKLog.info(f"new serialport_cfg: {cfg}"))

    # test revert to old slave_id
    device.set_serial_device_id(old_slave_id)
    device = create_device(client, old_slave_id)
    time.sleep(3)
    device.get_serialport_cfg(lambda cfg: SKLog.info(f"new serialport_cfg: {cfg}"))


def test_update_baudrate(device, client, baudrate):
    # 1. before set_serial_baudrate, get current serialport_cfg, should be old baudrate
    device.get_serialport_cfg(lambda cfg: SKLog.info(f"serialport_cfg: {cfg}"))
    # 2. set serial baudrate, device will reboot after baudrate changed
    device.set_serial_baudrate(baudrate=baudrate)
    # 3.wait 5s for device reboot
    time.sleep(5)
    # 4. re-create modbus client with new baudrate
    client_close(client)
    client = client_connect(port=serial_port_name, baudrate=baudrate)
    # 5. re-create device and set modbus client read/write registers callbacks
    device = create_device(client, device.slave_id)
    # 6.get new baudrate, should be new baudrate
    device.get_serialport_cfg(lambda cfg: SKLog.info(f"new serialport_cfg: {cfg}"))

def main():
  # Connect ModbusClient
  serial_port_name = "/dev/ttyUSB0" 
  old_baudrate = BaudRate.baudrate_115200
  new_baudrate = BaudRate.baudrate_57600
  client = client_connect(port=serial_port_name, baudrate=old_baudrate)
  if client is None:
      SKLog.error("Failed to open modbus serial port")
      return
  
  # Set the slave_id. After setting, the device will automatically restart.
  old_slave_id = 1 # default slave_id is 1 in Modbus Firmware
  new_slave_id = 2
  device = create_device(client, old_slave_id)
  # test_update_slave_id(device, client, new_slave_id)
  # exit(0)

  # Set the baud rate. After setting, the device will automatically restart.
  # test_update_baudrate(device, client, new_baudrate)
  # exit(0)

  #### Except for modifying slave_id and baud rate, other settings will not cause the device to restart. ####

  # Set force level
  SKLog.info(f"set_force_level")
  device.set_force_level(force_level=ForceLevel.full)
  # Force level: small/normal/full

  # Set Turbo mode for keep holding
  SKLog.info(f"set_turbo_mode")
  device.set_turbo_mode(True)
  device.get_turbo_mode(lambda turbo_mode: SKLog.info(f"get_turbo_mode, {turbo_mode}"))

  # Set automatic calibration position after power on
  SKLog.info(f"set_auto_calibration")
  device.set_auto_calibration(enabled=True)
  device.get_auto_calibration(lambda enabled: SKLog.info(f"auto_calibration_enabled: {enabled}"))

  # Close ModbusClient
  client_close(client)

Example Hand Close & Open

Key info:

  • Action Control: device.set_finger_positions([60, 60, 100, 100, 100, 100])
StarkSDK.init(isModbus=True, log_level=logging.INFO)

# Connect ModbusClient
serial_port_name = "/dev/ttyUSB0" 
broadcast_enable = True
client = client_connect(port=serial_port_name, baudrate=BaudRate.baudrate_115200, broadcast_enable=broadcast_enable)

# Initialize the device
slave_id = 0 if broadcast_enable else 1 # default slave_id is 1 in Modbus Firmware
device = StarkDevice.create_device(slave_id, f"{serial_port_name}_{slave_id}")

# Set register read/write callback
device.set_write_registers_callback(lambda register_address, values: client_write_registers(client, register_address, values=values, slave=slave_id))
device.set_read_holding_registers_callback(lambda register_address, count: client_read_holding_registers(client, register_address, count, slave=slave_id))
device.set_read_input_registers_callback(lambda register_address, count: client_read_input_registers(client, register_address, count, slave=slave_id))

# Make a fist
device.set_finger_positions([60, 60, 100, 100, 100, 100])
# Waiting for the action to complete
time.sleep(1)
# Open fist
device.set_finger_position(0) 
# device.set_finger_positions([0, 0, 0, 0, 0, 0])

# Close ModbusClient
client_close(client)

Example Action Sequence

Key info:

  • Action Control: device.set_finger_positions([60, 60, 100, 100, 100, 100])
#!/usr/bin/env python
import os
from modbus_client_utils import *

filename = os.path.basename(__file__).split('.')[0]
StarkSDK.init(isModbus=True, log_level=logging.INFO, log_file_name=f'{filename}.log', c_log_level=LogLevel.info)
pymodbus_apply_logging_config(level=logging.INFO)    

# Action sequence definition
sample_action_sequences = [
    {
        "index": 0,
        "duration_ms": 2000,
        "positions": [0, 0, 100, 100, 100, 100],
        "speeds": [10, 20, 30, 40, 50, 60],
        "forces": [5, 10, 15, 20, 25, 30]
    },
    {
        "index": 1,
        "duration_ms": 2000,
        "positions": [100, 100, 0, 0, 0, 0],
        "speeds": [15, 25, 35, 45, 55, 65],
        "forces": [6, 11, 16, 21, 26, 31]
    },
    {
        "index": 2,
        "duration_ms": 2000,
        "positions": [0, 0, 100, 100, 100, 100],
        "speeds": [10, 20, 30, 40, 50, 60],
        "forces": [5, 10, 15, 20, 25, 30]
    },
    {
        "index": 3,
        "duration_ms": 2000,
        "positions": [100, 100, 0, 0, 0, 0],
        "speeds": [15, 25, 35, 45, 55, 65],
        "forces": [6, 11, 16, 21, 26, 31]
    },
    {
        "index": 4,
        "duration_ms": 2000,
        "positions": [0, 0, 0, 0, 0, 0],
        "speeds": [15, 25, 35, 45, 55, 65],
        "forces": [6, 11, 16, 21, 26, 31]
    },
]

def action_sequence_info_to_list(action):
    return [action['index']] + [action['duration_ms']] + action['positions'] + action['speeds'] + action['forces']

def main():
    StarkSDK.set_error_callback(lambda error: SKLog.error(f"Error: {error.message}"))
    ports = serial_ports()
    SKLog.info(f"serial_ports: {ports}")
    if len(ports) == 0:
        return

    client = client_connect(port=serial_port_name, baudrate=BaudRate.baudrate_115200)
    if client is None:
        SKLog.error("Failed to open modbus serial port")
        return

    # new modbus device instance
    slave_id = 1
    device = StarkDevice.create_device(slave_id, f"{serial_port_name}_{slave_id}")

    # set modbus device write/read registers callbacks
    device.set_write_registers_callback(lambda register_address, values: client_write_registers(client, register_address, values=values, slave=slave_id))
    device.set_read_holding_registers_callback(lambda register_address, count: client_read_holding_registers(client, register_address, count, slave=slave_id))
    device.set_read_input_registers_callback(lambda register_address, count: client_read_input_registers(client, register_address, count, slave=slave_id))

    SKLog.info(f"Action Sequence: {len(sample_action_sequences)}")
    for action in sample_action_sequences:
        print(f"{action},")

    mapped_sequences = map(lambda action: action_sequence_info_to_list(action), sample_action_sequences)
    action_sequences = list(mapped_sequences)

    action_id = ActionSequenceId.default_gesture_fist

    # Test write action sequence
    # device.transfer_action_sequence(action_id, action_sequences=action_sequences)
    # # Test Save action sequence
    # device.save_action_sequence(action_id)

    # Test Read action sequence
    device.get_action_sequence(action_id, cb=lambda action_sequences: SKLog.info(f"get Action Sequence: {action_sequences}"))
    # Test Run action sequence
    device.run_action_sequence(action_id)

    client_close(client) 

if __name__ == "__main__":
    main()      

Upgrade OTA Upgrade

Key info:

  • ota_bin_path = ‘path/to/ota_bin.ota’   Replace ‘path/to/ota_bin.ota’ with your .ota file path.
StarkSDK.init(isModbus=True, log_level=logging.INFO)

event_loop = None
dfu_state = StarkDfuState.idle
dfu_progress = 0 # 0 ~ 1.0

def on_dfu_state_response(state):
    global dfu_state
    dfu_state = state
    SKLog.info(f"OTA state: {StarkSDK.dfu_state_to_string(dfu_state.value)}")
    if dfu_state == StarkDfuState.idle or dfu_state == StarkDfuState.aborted:
        SKLog.info(f"exit application")
        if event_loop is not None:
            event_loop.stop() 

def on_dfu_progress_response(progress):
    global dfu_progress
    dfu_progress = progress
    SKLog.info(f"OTA progress: {round(progress, 3)}")    
   
def main():
    # Connect ModbusClient
    serial_port_name = "/dev/ttyUSB0" 
    broadcast_enable = True
    client = client_connect(port=serial_port_name, baudrate=BaudRate.baudrate_115200, broadcast_enable=broadcast_enable)
    
    # Initialize the device
    slave_id = 0 if broadcast_enable else 1 # default slave_id is 1 in Modbus Firmware
    device = StarkDevice.create_device(slave_id, f"{serial_port_name}_{slave_id}")

    # set modbus device write registers callback
    device.set_write_registers_callback(lambda register_address, values: client_write_registers(client, register_address, values=values, slave=slave_id))

    # set ota callback
    device.set_dfu_read_callback(lambda: event_loop.run_in_executor(None, partial(on_dfu_read, client, device)))
    device.set_dfu_write_callback(lambda value: client_write_data(client, bytes(value)))
    device.set_dfu_state_callback(on_dfu_state_response)
    device.set_dfu_progress_callback(on_dfu_progress_response)

    ota_bin_path = 'path/to/ota_bin.ota'
    if not os.path.exists(ota_bin_path):
        SKLog.warning(f"OTA Missing: {ota_bin_path}")
    else:
        device.set_dfu_cfg(dfu_enabling_delay=4, dfu_enabling_interval=10, dfu_applying_delay=5)
        global dfu_state, dfu_progress
        dfu_state = StarkDfuState.idle
        dfu_progress = 0
        device.start_dfu(ota_bin_path)
        

    # keep the event loop running
    global event_loop
    event_loop = asyncio.get_event_loop()
    try:
        event_loop.run_forever()
    except KeyboardInterrupt:
        pass
    finally:
        event_loop.stop()
        if client is not None:
            client_close(client)

if __name__ == "__main__":
    main()

Need More Info?

Contact us for more details and help from our service team

请在浏览器中启用JavaScript来完成此表单。

Professional Robotics Solution

© 2024 Oceantrix

[email protected]
No.6688 HH Industrial Park. WF. 261000