Skip to main content
Version: 8

Websocket Client Library API

External system diagram

After you have built an application with MoveIt Pro, you may need to integrate it with a higher layer system, typically if you want to run application code that can be ROS agnostic.

This page focuses on using a Websocket Client Library to communicate with MoveIt Pro via rosbridge. If you are using a native ROS 2 Client Library (RCL) such as rclpy or rclcpp, see the Native ROS Client Library API.

Websocket client libraries connect to the rosbridge server and speak the rosbridge JSON protocol, allowing non-ROS applications to publish/subscribe, call services, and interact with ROS actions. Common websocket libraries include:

Setup

The MoveIt Pro Runtime runs a rosbridge server listening on port 3201. To connect to it across your network, expose that port in your robot's firewall settings.

The following examples are in Python but could be implemented in any of the languages above.

Running an Objective

To run an Objective from your application using websockets, send a goal to the /do_objective action.

For example, to communicate with MoveIt Pro from a Python script you can install the roslibpy library. Note that ROS2 action support is only available in the GitHub main branch, not yet in the pip release.

# Create and activate a virtual environment
python3 -m venv ~/roslibpy_venv
source ~/roslibpy_venv/bin/activate

# Install from GitHub main branch for ROS2 action support
pip install git+https://github.com/RobotWebTools/roslibpy.git@main

Note: Remember to activate the virtual environment (source ~/roslibpy_venv/bin/activate) before running your Python scripts that use roslibpy.

Here is an example Python script that will start the "Close Gripper" Objective via the DoObjectiveSequence action, wait for the result, and then print the outcome. Note that you will need to know the IP address of your robot if not running on the same machine.

import roslibpy
from roslibpy import ActionClient
import time

# Connect a client to the rosbridge running on the robot
# Replace the host with the IP of your robot
client = roslibpy.Ros(host='localhost', port=3201)

# Connect first before creating the action client
client.run()

# Define the action client for DoObjectiveSequence using ROS2 ActionClient
action = ActionClient(
client,
'/do_objective',
'moveit_studio_sdk_msgs/action/DoObjectiveSequence'
)

# Track completion
action_done = False
result_data = None

def on_result(result):
global action_done, result_data
print('Action completed!')
# The actual result data is in result['values']
error_code = result.get('values', {}).get('error_code', {})
print(f"Error code: {error_code.get('val', 'unknown')}")
print(f"Error message: {error_code.get('message', 'none')}")
result_data = result
action_done = True

def on_feedback(feedback):
print(f"Feedback: {feedback}")

def on_error(error):
global action_done
print(f"Error: {error}")
action_done = True

# Send goal
goal = {"objective_name": "Close Gripper"}
print(f"Sending goal: {goal['objective_name']}")

goal_id = action.send_goal(goal, on_result, on_feedback, on_error)
print(f"Goal ID: {goal_id}")

# Wait for result
print("Waiting for result...")
timeout = 30
start = time.time()
while not action_done and (time.time() - start) < timeout:
time.sleep(0.1)

if action_done:
print("Goal completed!")
else:
print("Timeout waiting for result")

# Clean up
client.terminate()

Running Objectives Synchronously vs. Asynchronously

The basic example above is synchronous - it waits for the action to complete. For asynchronous operation, you can send the goal and continue with other work while the action runs:

import roslibpy
from roslibpy import ActionClient
import time

# Connect first
client = roslibpy.Ros(host='localhost', port=3201)
client.run()

# Create action client after connection
action = ActionClient(client, '/do_objective', 'moveit_studio_sdk_msgs/action/DoObjectiveSequence')

action_done = False

# Asynchronous example with callbacks
def on_result(result):
global action_done
print('Close Gripper completed!')
error_code = result.get('values', {}).get('error_code', {})
print(f"Error code: {error_code.get('val', 'unknown')}")
action_done = True

def on_feedback(feedback):
print(f"Progress: {feedback}")

def on_error(error):
global action_done
print(f"Action failed: {error}")
action_done = True

# Send goal asynchronously
goal = {"objective_name": "Close Gripper"}
goal_id = action.send_goal(goal, on_result, on_feedback, on_error)
print(f"Started objective with goal ID: {goal_id}")

# Continue doing other work here
for i in range(5):
if action_done:
break
print(f"Doing other work... {i+1}/5")
time.sleep(1)

# Wait if not done
while not action_done:
time.sleep(0.1)

client.terminate()
warning

Only one Objective runs at a time. Sending a new goal will cancel any currently running Objective.

Cancelling Objectives

To explicitly cancel a running objective:

# Store the goal ID when sending
goal_id = action.send_goal(goal, on_result, on_feedback, on_error)

# Cancel it later
action.cancel_goal(goal_id)

Note: Cancellation currently triggers the error callback.

Through the rosbridge protocol you have access to the full ROS messaging system inside MoveIt Pro. Some examples of projects you could build using this interface:

  • Webapp UI
  • Machine Learning Image Pipeline
  • Multi-Robot Coordination
  • Factory Controller
  • Mobile App

Websockets are useful when you need to interact with a ROS based robot system across a network.