Intro
In this tutorial we will learn how to integrate MoveIt in Isaac Sim with ROS2 on the SO-ARM101. The SO-ARM101 (or the older version SO-ARM100) is an open-source dual-arm robot created by TheRobotStudio along with HuggingFace’s LeRobot for robotics research & education. MoveIt is used for robot motion planning, manipulation, and control in ROS2 allowing to control the real robot from simulation. However this tutorial is “simulation only”. A Sim2Real will follow in the future!
Watch the video here:
www.youtube.com
www.youtube.com
🤖 Don’t have a SO-ARM? → Buy one with a Discount: LYCHEEAI5 !
There are official vendors who sell all required parts and already assembled kits such as WowRobo from where I bought mine. I was very happy with the low cost, the quick delivery and also the awesome support from the founder himself, Leo Xiao, so I naturally asked for a collaboration and now I’m excited to announce that WowRobo is sponsoring this project. They also provide my community with a 5% discount to make learning robotics even more accessible!
You can get your own SO-ARM101 (or SO-ARM100) here using code LYCHEEAI5:
Make sure to “Add to cart” or choose “More payment options” in order to use the Discount Code!
WowRobo Robotics Store
shop.wowrobo.com
Prerequisites
- Isaac Sim → Installation Guide: Isaac Sim & Isaac Lab 
- Linux Ubuntu 22.04. ROS2 Humble - (Docker soon)
- ROS2 Humble Installation  ROS and ROS 2 Installation — Isaac Sim Documentation ROS and ROS 2 Installation — Isaac Sim Documentation
- Understanding ROS2 Basics; for example finishing the TurtleBot Tutorial
 Nex-dynamics robot Isaac Sim TurtleBot Crash Course: Complete ROS2 Navigation Guide for Beginners Nex-dynamics robot Isaac Sim TurtleBot Crash Course: Complete ROS2 Navigation Guide for Beginners
End Result (if you want to skip Step-By-Step Tutorial below or encounter issues)
 Embed GitHub Embed GitHub
- OLD_REPO Currently Quentin Deyna is working on a Docker Setup for “works-on-my-machine” Problems
- Clone the new repo and run MoveIt
# Clone the repository
git clone https://github.com/MuammerBay/SO-ARM101_MoveIt_IsaacSim.git
cd SO-ARM101_MoveIt_IsaacSim
# Source ROS 2
source /opt/ros/humble/setup.bash
# Update rosdep database
rosdep update
# Install ALL dependencies automatically
rosdep install --from-paths src --ignore-src -r -y
# Build the workspace
colcon build
# Source the workspace
source install/setup.bash
# Launch MoveIt demo
ros2 launch so_arm_moveit_config demo.launch.py- On a seperate terminal start Isaac Sim
# Source ROS 2
source /opt/ros/humble/setup.bash
# Run Isaac Sim with ros2 enabled
[ISAAC-SIM-4.5-FOLDER]/isaac-sim.selector.sh- Open the USD file (created from URDF)
- Start the Simulation (press Play)
- Move Robot in RViz
Step-By-Step Tutorial
ROS2 & MoveIt
- We will follow the Tutorial from robot maniaand apply it to our SO-ARM robot
- All credits to  YouTube robot mania. I highly recommend his channel as he covers a lot of very interesting topics! YouTube robot mania. I highly recommend his channel as he covers a lot of very interesting topics!
- First make sure you always source your ROS2 Humble in every terminal
- We will create a ROS workspace
- And get all the ROS2 Dependencies
- Prepare your MoveIt configuration & robot-description folder
- [YT: robot mania] How to Use MoveIt with Isaac Sim: A Step-by-Step Guide
source /opt/ros/humble/setup.bashmkdir -p ~/so-arm_moveit_isaacsim_ws/src
cd ~/so-arm_moveit_isaacsim_wssudo apt update
sudo apt install \
  ros-humble-moveit \
  ros-humble-ros2-control \
  ros-humble-ros2-controllers \
  ros-humble-gripper-controllers \
  ros-humble-topic-based-ros2-controlcd ~/so-arm_moveit_isaacsim_ws/src
mkdir -p so_arm_moveit_config
mkdir -p so_arm_description- First we will copy the URDF file for the SO-ARM from my newly created repo  Embed GitHub into the Embed GitHub into theso_arm_descriptionfolder
- What I’ve done is to copy the official URDF (NEW, to this day 26.05.) from and adjusted it for a proper ROS2 URDF format
- There are different URDF files for the SO-ARM100 & SO-ARM101, and I chose the new version of the SO-ARM101
- We will choose the newer urdf, please refer to this link to these links to know more about the differences
- https://github.com/TheRobotStudio/SO-ARM100/blob/main/Simulation/README.md
- https://github.com/TheRobotStudio/SO-ARM100/blob/main/Simulation/SO101/README.md
- Git clone the URDF repo.
- Build your workspace
- Launch the MoveIt Setup Assistant (see video above). # Make sure your workspace is sourced so it can find your robot_description package
- After the Setup: rebuild
- After Source and test (Before Isaac Sim Setup)
- Errors: Replace Integer with Float (see video above) in joint_limits.yaml
- Controller adjustment moveit_controllers.yaml. Add these to arm_controller
- After errors: rebuild again
- Now you can test MoveIt without Isaac Sim
Make sure to add a point . to the end of the git clone command to include only the files and not the folder. This is important for the URDF file
cd ~/so-arm_moveit_isaacsim_ws/src/so_arm_description
git clone https://github.com/MuammerBay/SO-ARM_ROS2_URDF.git .cd ~/so-arm_moveit_isaacsim_ws
colcon buildsource ~/so-arm_moveit_isaacsim_ws/install/setup.bash
ros2 launch moveit_setup_assistant setup_assistant.launch.pycd ~/so-arm_moveit_isaacsim_ws
colcon buildsource install/setup.bash
ros2 launch so_arm_moveit_config demo.launch.pyaction_ns: follow_joint_trajectory
default: truecolcon buildros2 launch so_arm_moveit_config demo.launch.pyIsaac Sim
- Open a terminal and source ROS
- Open Isaac Sim with the selector
- Import URDF
- See Tutorial for more information: Isaac Sim URDF Importer (SO-ARM)
- For the Stiffness & Damping use these values (from the Official Repo)
- stiffness= 17.8
- damping= 0.60
- Don’t forget to set the articulation root to the base mesh (xform)
- Create a pre-configured Action Graph for Isaac Sim ROS2 Bridge
- Here’s a video on more about this easy setup  Code Mechanics: My PhD Life in AI & Robotics IsaacSim+ROS2 Just Got MUCH Easier - Set Up A ROS2 Enabled Sensor in Minutes! Code Mechanics: My PhD Life in AI & Robotics IsaacSim+ROS2 Just Got MUCH Easier - Set Up A ROS2 Enabled Sensor in Minutes!
- (follow video instructions) Tools → Robotics →ROS2 Omnigraphs → Joint States
- Articulation to base mesh (xform)
- /isaac_joint_states
- /isaac_joint_command
- In src/so_arm_moveit_config/config/so101_new_calib.ros2_control.xacroadjust this
- To this:
- One last time: rebuild
- Open MoveIt in RViz
- Start the Simulation (press Play)
- Move Robot in RViz
source /opt/ros/humble/setup.bash[ISAAC-SIM-4.5-FOLDER]/isaac-sim.selector.sh				<ros2_control name="${name}" type="system">
				  <hardware>
				      <!-- By default, set up controllers for simulation. This won't work on real hardware -->
				      <plugin>mock_components/GenericSystem</plugin>
				  </hardware>        <ros2_control name="${name}" type="system">
            <hardware>
                <!-- By default, set up controllers for simulation. This won't work on real hardware -->
                <!-- plugin>mock_components/GenericSystem</plugin -->
                <plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
                <param name="joint_states_topic">/isaac_joint_states</param>
                <param name="joint_commands_topic">/isaac_joint_command</param>
            </hardware>cd ~/so-arm_moveit_isaacsim_ws
colcon buildsource install/setup.bash
ros2 launch so_arm_moveit_config demo.launch.py