Skip to content

viam-devrel/so-101

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

61 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

Viam SO-101 Robotic Arm Module

This is a Viam module for the SO-101 5-DOF + Gripper collaborative robotic arm designed by TheRobotStudio and HuggingFace. It can be used to control either the leader or follower arm, as well as configuring both has separate arm components for mirrored teleoperation!

Note

For more information on modules, see Modular Resources.

This SO-101 module is particularly useful in applications that require the SO-101 arm to be operated in conjunction with other resources (such as cameras, sensors, actuators, CV) offered by the Viam Platform and/or separately through your own code.

First Time Arm Setup

If you are setting up the arm for the first time: You'll need to follow some prerequisite steps before using this module.

  1. Install LeRobot software
  2. Configure the motors
  3. Build the arm
  4. Calibrate the arm

Model devrel:so101:discovery

Automatic discovery service that detects connected arms and suggests component configurations for the calibration sensor, arm and gripper. It will also look for existing calibration files.

IF YOU ARE BUILDING THIS ARM FOR THE FIRST TIME: add the calibration sensor and follow the setup instructions

Usage:

  • save your robot configuration with this service
  • open the Test panel on service configuration card or view the Control tab
  • click "+ add component" for the relevant component you'd like to set up: arm, gripper, or calibration sensor

Troubleshooting

  1. Serial Connection Failed:
    • Check that the USB cable is properly connected
    • Verify the correct port (Linux: /dev/ttyUSB0, /dev/ttyACM0; Windows: COM3, COM4, etc.)
    • Ensure no other applications are using the serial port
    • Check USB permissions on Linux: sudo chmod 666 /dev/ttyUSB0

Model devrel:so101:arm

The arm component controls the first 5 joints of the SO-101: shoulder_pan, shoulder_lift, elbow_flex, wrist_flex, and wrist_roll.

Use the devrel:so101:discovery service to help with configuring this component automatically.

Follow the arm setup steps to learn how to set up the arm for the first time.

Configuration

{
  "port": "/dev/ttyUSB0"
}

Attributes

The following attributes are available for the arm component:

Name Type Inclusion Description
port string Required The serial port for communication with the SO-101 (see Communication section below).
calibration_file string Optional Path to the calibration file. If not provided, the module will attempt to read calibration from servo registers. If servo reads fail, uses default calibration values.
baudrate int Optional The baud rate for serial communication. Default is 1000000.
servo_ids []int Optional List of servo IDs for the arm joints. Default is [1, 2, 3, 4, 5].
timeout duration Optional Communication timeout. Default is system default.
visualize_ee_frame bool Optional When true, serves a colored XYZ coordinate-frame marker at the end-effector for the 3D viewer. Default is false.
speed_degs_per_sec float Optional Real per-joint speed cap enforced on the servos, in degrees per second. Each joint moves at this speed independently, so joints with longer travel finish later (planned motion stays smooth because the planner sends fine-grained waypoints). Default 50, valid range 3–180.
acceleration_degs_per_sec_per_sec float Optional Validated and stored but not yet enforced on hardware (planned follow-up). Default 100, valid range 10–500.

If you're building and setting up an arm for the first time, please see the calibration sensor component for setup instructions.

This may also be necessary if you see inaccuracy issues while controlling the arm.

Calibration Priority

The module uses this calibration priority:

  1. File-based - If calibration_file is configured and exists, load from file
  2. Servo registers - If no file configured/found, read homing offset and range limits from servo hardware
  3. Hardcoded defaults - If servo reads fail, use default values (offset=0, range=500-3500)

The servo register fallback provides better out-of-box experience by using actual hardware settings instead of generic defaults. Each startup without a calibration file will re-read from servos to ensure fresh data.

Note: Calibration read from servos is used in-memory only and not automatically saved. To persist servo-read calibration, use the calibration sensor component's workflow.

Motion and speed

The hardware arm enforces a real per-joint speed cap on the Feetech servos: each joint moves at the configured speed_degs_per_sec (or the per-move override, see below). Because joints move independently rather than coordinating arrival times, a joint with a larger travel angle will take longer to reach its target than one with smaller travel. For RDK motion-planned paths this remains smooth in practice because the planner generates many fine-grained waypoints, keeping per-waypoint joint displacements small.

MoveThroughJointPositions accepts an optional MoveOptions.MaxVelRads (in radians/second) that overrides the configured default for that move. MaxAccRads is accepted but intentionally ignored — acceleration is not yet enforced on hardware. GoToInputs routes through this same path.

MoveThroughJointPositions streams waypoints back-to-back: intermediate waypoints are commanded without waiting for the arm to settle (flythrough), and the arm waits to stop only after the final waypoint. As a result, intermediate waypoints are not guaranteed stop-points. GoToInputs shares this same streaming path.

IsMoving() reports whether a move call is currently in progress. On the internal safety-timeout edge case (a move times out waiting for servos to settle), IsMoving may briefly differ from whether the servos are physically moving.

Stop() does not currently interrupt an in-progress joint move: a move blocks until the servos settle (or the internal safety timeout elapses), so a Stop() issued mid-move takes effect only once that move returns. Interrupting in-flight motion is a planned follow-up.

acceleration_degs_per_sec_per_sec is validated and stored when set via config or set_acceleration DoCommand, but is not yet written to the servo hardware. Acceleration enforcement is a planned follow-up.

Communication

The SO-101 uses serial communication over USB with Feetech STS3215 servos. The module uses a shared controller architecture to manage all 6 servos while preventing resource conflicts when both arm and gripper components are used.

You can use the included discovery service or find the available serial port options from your machine's command line.

On MacOS, look for usbmodem or usbserial in the name:

you@machine: ls /dev/tty.*
/dev/tty.Bluetooth-Incoming-Port
/dev/tty.debug-console
/dev/tty.usbmodem58CD1767051

you@machine: ls /dev/cu.*
/dev/cu.Bluetooth-Incoming-Port
/dev/cu.debug-console
/dev/cu.usbmodem58CD1767051

On Linux, look for ACM or USB in the name:

you@machine: ls /dev/tty*
/dev/ttyACM0
/dev/ttyUSB0

On Windows, look for COM in the name:

you@machine: mode
COM0
COM1

DoCommand

The module provides several custom commands accessible through the DoCommand interface:

Set Torque Control

Enable or disable joint torque:

{
  "command": "set_torque",
  "enable": true
}

Ping Servos

Test communication with all servos:

{
  "command": "ping"
}

Controller Status

Check the shared controller status for debugging:

{
  "command": "controller_status"
}

Connection Diagnostics

Run comprehensive connection diagnostics:

{
  "command": "diagnose"
}

Verify Configuration

Verify servo configuration and communication:

{
  "command": "verify_config"
}

Reinitialize Servos

Reinitialize servo communication with retry attempts:

{
  "command": "reinitialize",
  "retries": 3
}

Test Servo Communication

Test communication and read positions from arm servos:

{
  "command": "test_servo_communication"
}

Reload Calibration

Reload calibration from file:

{
  "command": "reload_calibration"
}

Get Calibration

Retrieve current calibration data:

{
  "command": "get_calibration"
}

Set Speed

Update the per-joint speed cap at runtime without reconfiguring the component. set_speed is a key in the request map (not a "command" value). Valid range: 3–180 degrees/second.

{
  "set_speed": 60.0
}

Response:

{
  "speed_set": 60.0
}

Set Acceleration

Update the acceleration parameter at runtime. set_acceleration is a key in the request map (not a "command" value). Valid range: 10–500 degrees/second². Note: acceleration is validated and stored but not yet enforced on hardware.

{
  "set_acceleration": 150.0
}

Response:

{
  "acceleration_set": 150.0
}

Get Motion Parameters

Retrieve the current speed and acceleration values in use. get_motion_params is a key set to true in the request map (not a "command" value). Both set_speed and get_motion_params can be combined in one request.

{
  "get_motion_params": true
}

Response:

{
  "current_speed_degs_per_sec": 50.0,
  "current_acceleration_degs_per_sec_per_sec": 100.0
}

Model devrel:so101:simulated

The simulated arm component emulates the SO-101 arm entirely in software, with no hardware required. It shares the same kinematics as the devrel:so101:arm model, so it is useful for developing and testing configs, motion plans, and the 3D scene viewer without a physical robot.

When commanded to a joint configuration, the simulated arm interpolates its joints toward the target over time at a configurable speed, just like rdk's builtin simulated arm. It also serves 3D meshes for each link, so it renders as an SO-101 in the visualizer.

Configuration

{}

All attributes are optional, so the simulated arm works with an empty configuration.

Attributes

The following attributes are available for the simulated arm component:

Name Type Inclusion Description
speed_degs_per_sec float Optional How fast each joint travels toward its target, in degrees per second. Default is 90.
motion string Optional Name of the motion service used to plan MoveToPosition requests. Default is "builtin".
simulate_time bool Optional Whether a background goroutine advances the arm's position in real time. Default is true. (Tests set it to false to drive the simulated clock.)
visualize_ee_frame bool Optional When true, serves a colored XYZ coordinate-frame marker at the end-effector for the 3D viewer. Default is false.

Example configuration with attributes:

{
  "speed_degs_per_sec": 60
}

Behavior

  • MoveToJointPositions, MoveThroughJointPositions, and GoToInputs interpolate the joints toward each target over time; the calls block until the arm arrives.
  • MoveToPosition plans through the motion service. Because the SO-101 is a 5-DOF arm, it defaults the planner goal metric to position_only; pass your own goal_metric_type via extra to override.
  • JointPositions, EndPosition, Geometries, and IsMoving report the simulated state.

DoCommand

Get Motion Parameters

Retrieve the configured joint speed:

{
  "command": "get_motion_params"
}

Model devrel:so101:gripper

The gripper component controls the 6th servo of the SO-101, which functions as a parallel gripper.

Use the devrel:so101:discovery service to help with configuring this component automatically.

Follow the arm setup steps to learn how to set up the arm for the first time.

Configuration

{
  "port": "/dev/ttyUSB0"
}

Use the same port and calibration_file configuration as the associated arm component.

Attributes

Name Type Inclusion Description
port string Required The serial port for communication with the SO-101.
calibration_file string Optional Path to the calibration file (shared with arm component).
baudrate int Optional The baud rate for serial communication. Default is 1000000.
servo_id int Optional The servo ID for the gripper. Default is 6.
timeout duration Optional Communication timeout. Default is system default.
gripper_type string Optional Which gripper meshes Geometries() serves for the 3D viewer: follower (moving jaw, default) or leader (thumb-loop handle + trigger). The moving part articulates with the live gripper opening.

Communication

You can use the included discovery service or find the available serial port options from your machine's command line.

On MacOS, look for usbmodem or usbserial in the name:

you@machine: ls /dev/tty.*
/dev/tty.Bluetooth-Incoming-Port
/dev/tty.debug-console
/dev/tty.usbmodem58CD1767051

you@machine: ls /dev/cu.*
/dev/cu.Bluetooth-Incoming-Port
/dev/cu.debug-console
/dev/cu.usbmodem58CD1767051

On Linux, look for ACM or USB in the name:

you@machine: ls /dev/tty*
/dev/ttyACM0
/dev/ttyUSB0

On Windows, look for COM in the name:

you@machine: mode
COM0
COM1

DoCommand

The gripper component provides several custom commands:

Get Gripper Position

Get the current gripper position:

{
  "command": "get_position"
}

Set Gripper Position

Set the gripper to a specific servo position:

{
  "command": "set_position",
  "servo_position": 2000
}

Controller Status

Check the shared controller status:

{
  "command": "controller_status"
}

Model devrel:so101:simulated-gripper

The simulated gripper emulates the SO-101 gripper entirely in software, with no hardware required. It serves the gripper meshes (a static body plus a moving jaw/trigger) to the 3D scene viewer, with the moving part posed by the gripper's opening — useful for developing and previewing without a physical robot.

Open opens the gripper and Grab closes it, interpolating the jaw open/closed over time so it animates in the 3D viewer (like the simulated arm). Both block until the motion finishes, and IsMoving reports true while the jaw is travelling. A simulated gripper never grasps an object, so Grab always reports false.

Configuration

{}

All attributes are optional, so the simulated gripper works with an empty configuration.

Attributes

Name Type Inclusion Description
gripper_type string Optional Which gripper meshes to serve: follower (moving jaw, the default) or leader (thumb-loop handle + trigger).

DoCommand

Set Position

Set a target opening percentage (0 = closed, 100 = open); the jaw interpolates toward it:

{
  "command": "set_position",
  "percentage": 50
}

Get Position

{
  "command": "get_position"
}

Model devrel:so101:calibration

When assembling the SO-101 arm from a kit, it requires calibration to map servo positions to joint angles based on how the arm was assembled.

The SO-101 Calibration Sensor provides a calibration workflow integrated into Viam's component system. It guides you through the calibration process using DoCommand calls and provides status updates through sensor readings.

IF YOU ARE SETTING UP THIS ARM FOR THE FIRST TIME: Follow the arm setup steps to learn how to set up the arm for the first time.

See the Setup Application for a visual walkthrough experience that uses this component.

If you have already calibrated the servos on this arm, use the devrel:so101:discovery service to help with configuring this component automatically.

Configuration

{
  "port": "/dev/ttyUSB0",
  "calibration_file": "my_awesome_arm.json"
}

Attributes

Name Type Required Description
port string Required Serial port for servo communication (see Communication section below)
calibration_file string Optional Path where calibration will be saved. If relative path, uses $VIAM_MODULE_DATA directory. Default: "so101_calibration.json"
baudrate int Optional Serial communication speed. Default: 1000000
timeout duration Optional Communication timeout. Default: "5s"

Communication

You can use the included discovery service or find the available serial port options from your machine's command line.

On MacOS, look for usbmodem or usbserial in the name:

you@machine: ls /dev/tty.*
/dev/tty.Bluetooth-Incoming-Port
/dev/tty.debug-console
/dev/tty.usbmodem58CD1767051

you@machine: ls /dev/cu.*
/dev/cu.Bluetooth-Incoming-Port
/dev/cu.debug-console
/dev/cu.usbmodem58CD1767051

On Linux, look for ACM or USB in the name:

you@machine: ls /dev/tty*
/dev/ttyACM0
/dev/ttyUSB0

On Windows, look for COM in the name:

you@machine: mode
COM0
COM1

Usage

Monitor Progress

Example output:

{
  "calibration_state": "range_recording",
  "instruction": "Recording range of motion. Move all joints through their full ranges.",
  "available_commands": ["stop_range_recording", "abort"],
  "servo_count": 5,
  "recording_time_seconds": 15.3,
  "position_samples": 306,
  "joints": {
    "shoulder_pan": {
      "id": 1,
      "current_position": 2150,
      "homing_offset": -103,
      "recorded_min": 758,
      "recorded_max": 3292,
      "is_completed": false
    }
  }
}

Available Commands

{
  "command": "command_name"
}

Workflow Commands

Command Description Required State
start Begin calibration workflow idle, completed, error
set_homing Set homing offsets and write to servo registers started
start_range_recording Begin recording servo ranges homing_position
stop_range_recording Complete range recording range_recording
save_calibration Write limits to servos and save file completed
abort Cancel calibration Any
reset Reset to initial state error

Utility Commands

Command Description
get_current_positions Read current servo positions

Motor Setup Commands

The calibration sensor also provides motor setup commands for initial SO-101 servo configuration. These commands implement the systematic motor setup process described in MOTOR_SETUP.md and are separate from the calibration workflow.

Command Description Parameters
motor_setup_discover Discover a single motor connected to the bus motor_name (string): Motor name (e.g., "gripper", "wrist_roll")
motor_setup_assign_id Assign target ID and baudrate to discovered motor motor_name (string), current_id (int), target_id (int), current_baudrate (int)
motor_setup_verify Verify all SO-101 motors are properly configured None
motor_setup_scan_bus Scan the entire bus for connected servos None
motor_setup_reset_status Reset motor setup status None

Motor Setup Workflow

The motor setup process should be performed in reverse order (gripper → shoulder_pan) to avoid ID conflicts:

  1. Connect only one motor (e.g., gripper) to the controller
  2. Discover: {"command": "motor_setup_discover", "motor_name": "gripper"}
  3. Assign ID: {"command": "motor_setup_assign_id", "motor_name": "gripper", "current_id": 1, "target_id": 6, "current_baudrate": 57600}
  4. Repeat for each motor in order: wrist_roll → wrist_flex → elbow_flex → shoulder_lift → shoulder_pan
  5. Verify: {"command": "motor_setup_verify"} (connect all motors)

Motor Setup Status

Motor setup status is included in sensor readings:

{
  "motor_setup": {
    "in_progress": false,
    "step": 0,
    "status": "Motor setup ready"
  }
}

State Machine

The calibration sensor operates as a state machine:

  • idle: Ready to start calibration
  • started: Torque disabled, ready for homing position
  • homing_position: Homing set, ready for range recording
  • range_recording: Recording min/max positions
  • completed: Calibration data ready to save
  • error: Error occurred, use reset command

Calibration File Output

The sensor saves calibration in the standard format:

{
  "shoulder_pan": {
    "id": 1,
    "drive_mode": 0,
    "homing_offset": -1470,
    "range_min": 758,
    "range_max": 3292,
    "norm_mode": 3
  },
  "shoulder_lift": {
    "id": 2,
    "drive_mode": 0,
    "homing_offset": 157,
    "range_min": 612,
    "range_max": 3401,
    "norm_mode": 3
  },
  "gripper": {
    "id": 6,
    "drive_mode": 0,
    "homing_offset": 1407,
    "range_min": 2031,
    "range_max": 3476,
    "norm_mode": 1
  }
}

Troubleshooting

Common Issues

  • Range recording not working: Ensure you call start_range_recording and manually move joints
  • Invalid ranges: Move joints through their complete range of motion
  • Servo communication errors: Check port, baudrate, and servo connections
  • Permission denied: Ensure proper access to serial port (sudo chmod 666 /dev/ttyUSB0)

Troubleshooting

Connection Issues

  1. Serial Connection Failed:

    • Check that the USB cable is properly connected
    • Verify the correct port (Linux: /dev/ttyUSB0, /dev/ttyACM0; Windows: COM3, COM4, etc.)
    • Ensure no other applications are using the serial port
    • Check USB permissions on Linux: sudo chmod 666 /dev/ttyUSB0
  2. Servo Communication Errors:

    • Verify servo IDs are correctly configured (1-6)
    • Check calibration file path and format
    • Use the diagnose DoCommand for detailed diagnostics
    • Try reinitializing with the reinitialize DoCommand
  3. Shared Controller Conflicts:

    • Check controller status using the controller_status DoCommand
    • Ensure consistent configuration across arm and gripper components
    • Verify the same serial port and baudrate are used
    • Restart components if configuration changes are needed

Hardware Setup

  1. Power: Connect the properly rated power adapter to the arm's controller board, either 5-7.4V or 12V depending on your servos
  2. USB Communication: Connect the USB cable between the controller board and your computer
  3. Servo Connections: Ensure all servos are properly daisy-chained with 3-pin cables
  4. Initial Position: Manually position the arm in a safe configuration before powering on

Safety Notes

Warning

  • Always ensure the arm's workspace is clear before operation
  • The arm can move quickly - maintain safe distances during operation
  • Use the torque control features to enable safe manual positioning when needed
  • Proper calibration is essential for safe operation within expected ranges

Setup Application

This module includes a web-based setup application that provides guided workflows for configuring your SO-101 robotic arm. The application is hosted as a Viam App and automatically deployed with each module version.

Access the Setup App: https://so101-setup_devrel.viamapplications.com

Add an extra / to the end of the URL if you see a "404 Not Found" after authenticating.

Available Workflows

The setup application provides three main workflows to guide you through different aspects of SO-101 configuration:

Full Setup (Recommended)

Complete setup workflow from unboxed hardware to fully configured and calibrated SO-101 arm. This comprehensive process includes:

  • Hardware connection verification
  • Motor ID configuration for all servos (1-6)
  • Joint calibration with homing positions and range limits
  • Final system testing and validation

Motor Setup Only

Configure servo IDs and communication parameters for SO-101 motors. Use this workflow when you need to:

  • Set up servos with proper IDs (1-6) from factory defaults
  • Configure communication baudrate (1,000,000 bps)
  • Verify motor connectivity and response
  • Resolve servo ID conflicts

Calibration Only

Calibrate joint ranges and homing positions for arms with already configured motors. This workflow covers:

  • Setting homing positions for all joints
  • Recording joint range limits through guided manual movement
  • Saving calibration data in the proper format
  • Verifying calibration accuracy

Using the Setup Application

  1. Connect to your robot: The app integrates directly with your Viam machine through the Viam SDK
  2. Select your workflow: Choose from Full Setup, Motor Setup Only, or Calibration Only
  3. Follow guided steps: The application provides clear instructions and real-time feedback
  4. Save configuration: Calibration data is automatically saved and applied to your SO-101 components

The setup application provides an intuitive alternative to the DoCommand-based calibration workflow described in the devrel:so101:calibration component documentation above.

SO-101 Resources

For more information about the SO-101 robotic arm: