Mobile Robot Controllers#

Differential controller#

The differential controller uses the speed differential between the left and right wheels to control the robot’s linear and angular velocity. The differential robot enables the robot to turn in place and is used in the NVIDIA Nova Carter robot.

Nova Carter

The Math#

\[ \begin{align}\begin{aligned}\omega_R &= \frac{1}{2r}(2V + \omega l_{tw})\\\omega_L &= \frac{1}{2r}(2V - \omega l_{tw})\end{aligned}\end{align} \]

where \(\omega\) is the desired angular velocity, \(V\) is the desired linear velocity, \(r\) is the radius of the wheels, and \(l_{tw}\) is the distance between them. \(\omega_R\) is the desired right wheel angular velocity and \(\omega_L\) is the desired left wheel angular velocity.

OmniGraph Node#

Differential Controller Omnigraph Inputs#

Input Commands

description

execIn

Input execution

wheelRadius

radius of the wheels

wheelDistance

distance between the wheels

dt

delta time

maxAcceleration

max linear acceleration for moving forward and reverse, 0.0 means not set

maxDeceleration

max linear breaking of the robot, 0.0 means not set

maxAngularAcceleration

max angular acceleration of the robot, 0.0 means not set

maxLinearSpeed

max linear speed allowed for the robot, 0.0 means not set

maxAngularSpeed

max angular speed allowed for the robot, 0.0 means not set

maxWheelSpeed

max wheel speed

Desired Linear Velocity

desired linear velocity

Desired Angular Velocity

desired angular velocity

Differential Controller Omnigraph Outputs#

Output Commands

description

VelocityCommand

velocity command for the left and right wheel

Python#

The code snippet below setups the differential controller for a robot with a wheel radius of 3 cm and a base of 11.25cm, with a linear speed of 0.3m/s and angular speed of 1.0rad/s.

 1from isaacsim.robot.wheeled_robots.controllers.differential_controller import DifferentialController
 2
 3wheel_radius = 0.03
 4wheel_base = 0.1125
 5controller = DifferentialController("test_controller", wheel_radius, wheel_base)
 6
 7linear_speed = 0.3
 8angular_speed = 1.0
 9command = [linear_speed, angular_speed]
10actions = controller.forward(command)

Holonomic Controller#

The holonomic controller computes the joint drive commands required on omni-directional robots to produce the commanded forward, lateral, and yaw speeds of the robot. An example of a holonomic robot is the NVIDIA Kaya robot. The problem is framed as a quadratic program to minimize the residual “net force” acting on the center of mass.

Kaya

Note

The wheel joints of the robot prim must have additional attributes to definine the roller angles and radii of the mecanum wheels.

1stage = omni.usd.get_context().get_stage()
2joint_prim = stage.GetPrimAtPath("/path/to/wheel_joint")
3joint_prim.CreateAttribute("isaacmecanumwheel:radius",Sdf.ValueTypeNames.Float).Set(0.12)
4joint_prim.CreateAttribute("isaacmecanumwheel:angle",Sdf.ValueTypeNames.Float).Set(10.3)

The HolonomicRobotUsdSetup class automates this process.

The Math#

The cost funciton is defined as the control input to the robot joints. By minimizing the control inputs, excess acceleration and be reduced.

\[J = min(X^T \cdot X)\]

The equality constrains are set by the linear and angular target velocity Inputs:

\[ \begin{align}\begin{aligned}v_{input} &= V^T \cdot X\\w_{input} &= (V \times D_{wheel dist to COM}) \cdot X\end{aligned}\end{align} \]

OmniGraph Node#

Holonomic Controller Omnigraph Inputs#

Input Commands

description

execIn

Input execution

wheelRadius

Array of wheel radius

wheelPositions

position of the wheel with respect to chassis’ center of mass

wheelOrientations

orientation of the wheel with respect to chassis’ center of mass frame

mecanumAngles

angles of the mecanum wheels with respect to wheel’s rotation axis

wheelAxis

the rotation axis of the wheels

upAxis

The up axis (default to z axis)

Velocity Commands for the vehicle

velocity in x and y and rotation

maxLinearSpeed

maximum speed allowed for the vehicle

maxAngularSpeed

maximum angular rotation speed allowed for the vehicles

maxWheelSpeed

maximum rotation speed allowed for the wheel joints

linearGain

gain for the linear velocity input

angularGain

gain for the angular input input

Holonomic Controller Omnigraph Outputs#

Output Commands

description

jointVelocityCommand

velocity command for the wheel joints

Python#

The code snippet below computes the joint velocity output for a three wheeled holonomic robot with command velocity of [1.0, 1.0, 0.1]

 1 from isaacsim.robot.wheeled_robots.controllers.holonomic_controller import HolonomicController
 2
 3 wheel_radius = [0.04, 0.04, 0.04]
 4 wheel_orientations = [[0, 0, 0, 1], [0.866, 0, 0, -0.5], [0.866, 0, 0, 0.5]]
 5 wheel_positions = [
 6    [-0.0980432, 0.000636773, -0.050501],
 7    [0.0493475, -0.084525, -0.050501],
 8    [0.0495291, 0.0856937, -0.050501],
 9 ]
10 mecanum_angles = [90, 90, 90]
11 velocity_command = [1.0, 1.0, 0.1]
12
13 controller = HolonomicController(
14    "test_controller", wheel_radius, wheel_positions, wheel_orientations, mecanum_angles
15 )
16 actions = controller.forward(velocity_command)

Ackermann Controller#

The ackeramnn controller is commonly used for robots with steerable wheels, an example of steerable robot is the NVIDIA leatherback robot. The ackeramnn controller in Isaac Sim will assume the desired steering angle and linear velocity is provided, and based on the robot geometry

Leatherback

The Math#

Compute the steering angle offset between the left and right steering wheels:

\[ \begin{align}\begin{aligned}R_{icr} &= \frac{l_{wb}}{tan(\theta_{steer})}\\\theta_L &= \arctan[\frac{l_{wb}}{R_{icr} - 0.5 * l_{tw}}]\\\theta_R &= \arctan[\frac{l_{wb}}{R_{icr} + 0.5 * l_{tw}}]\end{aligned}\end{align} \]

where \(R_{icr}\) is the radius to the instantaneous center of rotation, \(\theta_{steer}\) is the desired steering angle, \(l_{wb}\) is the distance between rear and front axles (wheel base), \(l_{tw}\) is the track width

Compute the individual wheel velocities (Forward steering case):

First step is to find the distance between the wheels and the instantaneous center of rotation.

\[ \begin{align}\begin{aligned}D_{front} &= \sqrt{ (R_{icr} \pm 0.5 l_{tw})^2 + (l_{wb})^2 }\\D_{rear} &= R_{icr} \pm 0.5 l_{tw}\end{aligned}\end{align} \]

Note

for \(\pm\), use \(-\) for the wheel closer to the \(R_{icr}\) and \(+\) for the wheel further to the \(R_{icr}\)

Then desired wheel velocity can be computed

\[ \begin{align}\begin{aligned}\omega_{front} &= \frac{V_{desired}}{R_{icr}} \cdot \frac{D_{front}}{r_{front}}\\\omega_{rear} &= \frac{V_{desired}}{R_{icr}} \cdot \frac{D_{rear}}{r_{rear}}\end{aligned}\end{align} \]

Where \(V_{desired}\) is the desired linear velocity, \(r_{front}\) is the desired front wheel radius, and \(r_{rear}\) is the desired rear wheel radius.

OmniGraph Node#

Ackermann Controller Omnigraph Inputs#

Input Commands

description

execIn

Input execution

acceleration

Desired forward acceleration for the robot in m/s^2

speed

Desired forward speed in m/s

steeringAngle

Desired steering angle in radians, by default it is positive for turning left for a front wheel drive

currentLinearVelocity

Current linear velocity of the robot in m/s

wheelBase

Distance between the front and rear axles of the robot in meters

trackWidth

Distance between the left and right rear wheels of the robot in meters

turningWheelRadius

Radius of the front wheels of the robot in meters

maxWheelVelocity

Maximum angular velocity of the robot wheel in rad/s

invertSteeringAngle

Flips the sign of the steering angle, Set to true for rear wheel steering

useAcceleration

Use acceleration as an input, Set to false to use speed as input instead

maxWheelRotation

Maximum angle of rotation for the front wheels in radians

dt

Delta time for the simulation step

Ackermann Controller Omnigraph Outputs#

Output Commands

description

execOut

Output execution

leftWheelAngle

Angle for the left turning wheel in radians

rightWheelAngle

Angle for the right turning wheel in radians

wheelRotationVelocity

Angular velocity for the turning wheels in rad/s

Python#

The python snippet below creates an ackerrmann controller for a robot with a wheel base of 1.65m, trackwidth of 1.25m, and wheel radius of 0.25m, sending it a desired forward velocity of 1.1 rad/s and steering angle of 0.1rad.

 1from isaacsim.robot.wheeled_robots.controllers.ackermann_controller import AckermannController
 2
 3wheel_base = 1.65
 4track_width = 1.25
 5wheel_radius = 0.25
 6desired_forward_vel = 1.1  # rad/s
 7desired_steering_angle = 0.1  # rad
 8
 9# Setting acceleration, steering velocity, and dt to 0 to instantly reach the target steering and velocity
10acceleration = 0.0  # m/s^2
11steering_velocity = 0.0  # rad/s
12dt = 0.0  # secs
13
14controller = AckermannController(
15   "test_controller", wheel_base=wheel_base, track_width=track_width, front_wheel_radius=wheel_radius
16)
17
18actions = controller.forward(
19      [desired_steering_angle, steering_velocity, desired_forward_vel, acceleration, dt]
20)