Robot Arm
Example Robots
Topic name |
Topic type |
About |
---|---|---|
joint_states |
joint state command |
Robot arm are designed to be controlled by joint state msg and publish joint state msg.
$ ros2 topic pub /arm/ue_joint_commands sensor_msgs/msg/JointState "{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''}, name: ['joint12', 'joint23', 'joint34'], position: [1.57,1.57,1.57], velocity: [], effort: []}"
SimpleArm
Example map is at turtlebot3-UE/Content/Maps/RobotArmExample.umap
- BP_KinematicSimpleArm
Example kinematic robot implementation in BP.
This BP class is child class of ARRBaseRobot and added joint and link setting.
In Construction script in BP, all joint and link relations are set. JointName which is used by ROS 2 is also set in here.
UR10
These BP class are child class of ARRBaseRobot and added joint and link setting.
Example map is at turtlebot3-UE/Content/Maps/RobotArmExample.umap
reference: Universal_Robots_ROS2_Description

In Construction script in BP, all joint and link relations are set. JointName which is used by ROS 2 is also set in here.
These robots can be controlled with ur_description package.
sudo apt install ros-humble-ur-description
ros2 launch ur_description view_ur.launch.py ur_type:=ur10
JointCmdTopicName of ROS2Interface is changed to joint_states to control with view_ur.launch

- BP_KinematicUR10
Joints are URRKinematicJointComponent
- BP_PhysicsUR10
Joints are URRPhysicsJointComponent
Panda
These BP class are child class of ARRBaseRobot and added joint and link setting.
Panda arm is example to be controlled with moveit2.
Example map is at turtlebot3-UE/Content/Maps/RobotArmExample.umap and turtlebot3-UE/Content/Maps/RobotArmExample.umap .
reference: How To Command Simulated Isaac Robot

In Construction script in BP, all joint and link relations are set. JointName which is used by ROS 2 is also set in here.
ROS2Interface has set isaac_joint_commands and isaac_joint_states as topic names to be controlled with topic_based_ros2_control example,
To build moveit2 ws
mkdir -p colcon_ws/src
cd colcon_ws/src
git clone https://github.com/ros-planning/moveit2_tutorials.git
cd moveit2_tutorials && git checkout 7c156304e
cd .. && vcs import < moveit2_tutorials/moveit2_tutorials.repos
git clone https://github.com/PickNikRobotics/topic_based_ros2_control.git
cd .. && colcon build --mixin release
*this is move2 setup with topic_based_ros2_control
To run moveit2 ws
source colcon_ws/install/setup.bash
ros2 launch moveit2_tutorials isaac_demo.launch.py
- BP_KinematicPanda
Joints are URRKinematicJointComponent
- BP_PhysicsPanda
Joints are URRPhysicsJointComponent
Custom Robot Creation TIPS
To create custom mobile robot
- Create child class of ARRBaseRobot
- Overwrite default parameters.
Set bMobileRobot false.
Configure meshes and joints in BP
Configure construction script to set joint and link relations similar as BP_KinematicSimpleArm.
If you want to dynamically spawn robots and pass random parameters, overwrite InitPropertiesFromJSON()
- Create child class of URRROS2Interfaces
Overwrite default parameters such as topic name.
Add necessary ROS Interfaces. Please also refer rclUE tutorials.
Create ROS 2 Service client of /SpawnEntity and pass necessary parameters outside of UE if you want to dynamically spawn robots from outside of UE