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:

pip install 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
import roslibpy.actionlib

# 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)

# Define the action client for DoObjectiveSequence
action = roslibpy.actionlib.ActionClient(
client,
'/do_objective',
'moveit_studio_sdk_msgs/action/DoObjectiveSequence'
)

client.run()

# Define the goal (objective) message
goal = roslibpy.actionlib.Goal(action, roslibpy.Message({"objective_name": "Close Gripper"}))

# Send the goal and wait for the result
goal.send()
result = goal.wait()

print('Error code:', result.get('error_code'))
print('Error message:', result.get('error_message'))

action.dispose()
client.terminate()

Running Objectives Synchronously vs. Asynchronously

  • Synchronous: call goal.send() then goal.wait() to block until the result is available, then send the next goal.
  • Asynchronous: register a result callback and return immediately, allowing your app to continue other work.
import roslibpy
import roslibpy.actionlib

client = roslibpy.Ros(host='localhost', port=3201)
action = roslibpy.actionlib.ActionClient(client, '/do_objective', 'moveit_studio_sdk_msgs/action/DoObjectiveSequence')
client.run()

# Asynchronous example with a result callback
goal = roslibpy.actionlib.Goal(action, roslibpy.Message({"objective_name": "Close Gripper"}))

def on_result(result):
print('Close Gripper result:', result)

goal.on('result', on_result)
goal.send()

# ... continue doing other work here ...

# When finished
action.dispose()
client.terminate()
warning

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

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.