ROS TurtleBot3 Sample

Importing TurtleBot3 URDF

To import the TurtleBot3 into Omniverse Isaac Sim first convert the .xacro file to .urdf file by calling

1
rosrun xacro xacro -o <output_name>.urdf <input_file>.urdf.xacro

For this example we will be using the TurtleBot3 Burger model. Once converted to .urdf, use the URDF Importer (Isaac Utils -> URDF Importer) to import TurtleBot3.

  • Uncheck “Merge Fixed Joints”

  • Uncheck “Fix Base Link” in the importing settings.

  • Under Parser set the joint drive type to Velocity so that wheels can be properly driven later.

TurtleBot needs a surface to drive on, so add a ground plane by going to Create -> Physics -> Ground Plane. Drag the new GroundPlane prim so it is under /World

../_images/isaac_turtlebot_urdf-importer.png

TurtleBot Setup

There are several parameters on the TurtleBot that we need to tune in order for it to run smoothly. We will first add friction properties to both the wheels and the ground. Then we will modify the velocity driver parameters so that the wheels can be controlled properly.

Adding Physics Material

Go to Create -> Physics -> Physics Material. You can rename the material by double clicking PhysicsMaterial on the Stage Tree. In this case the material was renamed to RearSlider and is under the main robot USD prim at turtlebot3_burger. Set the Friction Combine Mode of this material to min so that any contact interactions with this material are treated as frictionless.

Then we assign this new zero friction material to the rear block by selecting the /turtlebot3_burger/caster_back_link/collisions prim and under the Property tab go down to the Physics materials on selected models section and assign the material as shown.

pic2 pic3

Velocity Control Setup

Mobile robots are usually velocity controlled.

  1. Find the target joint on the Stage tree. In this case, it’s the two wheel joints, “wheel_left_joint”, and “wheel_right_joint”, under the “base_link” prim.

  2. Under the Drive section in the Property tab the Damping parameter is used to control the strength of the velocity drive.

  3. Increase the Damping parameter to a larger value, like 100000000.0, to make them stronger.

  4. To test the velocity drives, press the play button and then set the target velocity (in deg/s) in the Drive section in the Property tab to a non-zero value. If you set both drives to 360.0 deg/s the robot should drive forwards

../_images/isaac_turtlebot_velocity-drive.png

Running TurtleBot via ROS

To run TurtleBot through ROS interface. We need to connect the robot through a ROS bridge.

  1. To add a joint state rostopic, go to Create -> Isaac -> ROS and add Joint State. The rostopics /joint_state and /joint_command will automatically start. Nothing will be published on the /joint_state until it is connected to the robot of your choice.

  2. Select ROS_JointState on the stage tree, under the Property tab, inside Raw USD Properties, click on Add Target(s). Add the path to the root articulation , /turtlebot3_burger1 of the turtlebot to the articulationPrim property.

  3. Press play on the editor, and joint information will start publishing on the /joint_state rostopic. and /joint_command is ready to receive joint commands.

../_images/isaac_turtlebot_ros-control.png

Please refer to ROS & ROS2 Bridge for more details on ROS Bridge.

On the ROS side ensure that a ROS master node is running and then execute the following to make the robot drive forward.

 1
 2
 3
 4
 5
 6
 7
 8
 9
10
11
12
13
14
15
16
17
18
    import rospy
    from sensor_msgs.msg import JointState
    import numpy as np
    import time

    rospy.init_node("turtlebot_bridge", anonymous=True)

    pub = rospy.Publisher("/joint_command", JointState, queue_size=10)
    rate = rospy.Rate(2)
    joint_state = JointState()

    joint_state.name = ["wheel_left_joint", "wheel_right_joint"]
    num_joints = len(joint_state.name)

    joint_state.velocity = np.array([3.14]* num_joints)
    while not rospy.is_shutdown():
        pub.publish(joint_state)
        rate.sleep()