Wheeled Robots [omni.isaac.wheeled_robots]

The omni.isaac.wheeled_robots extension provides controllers, utilities, and omnigraph nodes for simulating wheeled robots in isaac sim.

Basic Usage

The classes and controllers provided by omni.isaac.wheeled_robots are designed to be run within the world simulation context provided by omni.isaac.core. Like many other classes provided by core, wheeled_robots are created by wrapping prims already present on the stage in an interface class. This API is expected by world to do things like initialize and reset data structures, apply drive commands, retrieve joint states, etc…

Creating this interface means specifying the articulation being managed, the name that world will know this object by, and the names of the drivable joints

1# Assuming a stage context containing a Jetbot at /World/Jetbot
2from omni.isaac.wheeled_robots.robots import WheeledRobot
3jetbot_prim_path = "/World/Jetbot"
4
5#wrap the articulation in the interface class
6jetbot = WheeledRobot(prim_path=jetbot_prim_path,
7                      name="Joan",
8                      wheel_dof_names=["left_wheel_joint", "right_wheel_joint"]
9                     )

Commanding the robot should be done prior to the physics step using an ArticulationAction, a type provided by omni.isaac.core to facilitate things like mixed command modes (effort, velocity, and position) and complex robots with multiple types of actions that could be taken.

1from omni.isaac.core.utils.types import ArticulationAction
2
3action = ArticulationAction(joint_velocities = np.array([1.14, 1.42]))
4jetbot.apply_wheel_actions(action)

It is rarely the case however, that a user will want to command a robot by directly manipulating the joints, and so we also provide a suite of controllers to convert various types of general commands into specific joint actions. For example, you may want to control your differential base using throttle and steering commands…

1from omni.isaac.wheeled_robots.controllers import DifferentialController
2
3throttle = 1.0
4steering = 0.5
5controller = DifferentialController(name="simple_control", wheel_radius=0.035, wheel_base=0.1)
6jetbot.apply_wheel_actions(controller.forward(throttle, steering))

Controllers

Differential Controller


Holonomic Controller


Wheel Base Pose Controller


Robots

Wheeled Robot


Holonomic Robot USD Setup


Utilities

Quintic Polynomial


Quintic Polynomials Planner


Stanly Control


PID Control


OmniGraph Nodes

QuinticPathPlanner

Quintic Path Planner For Wheeled robots

Use odometry from a robot and a target position/prim to calculate a route from the robot’s starting position to the target position.

Inputs
  • execIn (execution): The input execution.

  • currentPosition (vectord[3]): Current position of the robot (recommended to use Get Prim Local to World Transform node).

  • currentOrientation (quatd[4]): Current rotation of the robot as a quaternion (recommended to use Get Prim Local to World Transform node).

  • targetPrim (target, optional): USD prim reference to the goal position/orientation prim.

  • targetPosition (vectord[3]): Target position (used if no targetPrim provided).

  • targetOrientation (quatd[4]): Target orientation (used if no targetPrim provided).

  • initialVelocity (double): Initial velocity. Default to 0.5.

  • initialAccel (double): Initial acceleration. Default to 0.02.

  • goalVelocity (double): Goal velocity. Default to 0.5.

  • goalAccel (double): Goal acceleration. Default to 0.02.

  • maxAccel (double): Max acceleration. Default to 1.5.

  • maxJerk (double): Max jerk. Default to 0.3.

  • step (double): Step. Default to 0.16666666667.

Outputs
  • execOut (execution): The output execution.

  • pathArrays (double[]): The path v, x, y, and yaw arrays.

  • target (double[3]): Target position and orientation.

  • targetChanged (bool): Target position/orientation has changed.

HolonomicRobotUsdSetup

setup any robot to be ready to be used by the holonomic controller by extract attributes from USD

Use this node to extract all the holonomic drive information from USD if the listed information are stored in the USD file already. If they are not in USD, you can manually set those values in the HolonomicController node

Inputs
  • robotPrim (target): prim for the robot’s articulation root.

  • comPrim (target): prim for the center of mass xform.

  • usePath (bool): use prim path instead of prim target. Default to False.

  • robotPrimPath (token): prim path to the robot’s articulation root link when usdPath is true.

  • comPrimPath (token): prim path to the robot’s center of mass xform.

Outputs
  • wheelRadius (double[]): an array of wheel radius.

  • wheelPositions (double[3][]): position of the wheel with respect to chassis’ center of mass.

  • wheelOrientations (double[4][]): orientation of the wheel with respect to chassis’ center of mass frame.

  • mecanumAngles (double[]): angles of the mechanum wheels with respect to wheel’s rotation axis.

  • wheelAxis (double[3]): the rotation axis of the wheels, assuming all wheels have the same.

  • upAxis (double[3]): the rotation axis of the vehicle.

  • wheelDofNames (token[]): name of the left wheel joint.

HolonomicController

Holonomic Controller

Calculating the desired wheel speeds when given a desired vehicle speed.

Inputs
  • execIn (execution): The input execution.

  • wheelRadius (double[]): an array of wheel radius.

  • wheelPositions (double[3][]): position of the wheel with respect to chassis’ center of mass.

  • wheelOrientations (double[4][]): orientation of the wheel with respect to chassis’ center of mass frame.

  • mecanumAngles (double[]): angles of the mecanum wheels with respect to wheel’s rotation axis.

  • wheelAxis (double[3]): the rotation axis of the wheels. Default to [1.0, 0.0, 0.0].

  • upAxis (double[3]): the rotation axis of the vehicle. Default to [0.0, 0.0, 1.0].

  • inputVelocity (double[3]): velocity in x and y and rotation.

  • maxLinearSpeed (double, optional): maximum speed allowed for the vehicle. Default to 100000.

  • maxAngularSpeed (double, optional): maximum angular rotation speed allowed for the vehicle. Default to 100000.

  • maxWheelSpeed (double, optional): maximum rotation speed allowed for the wheel joints. Default to 100000.

  • linearGain (double): linear gain. Default to 1.

  • angularGain (double): angular gain. Default to 1.

Outputs
  • jointVelocityCommand (double[]): velocity commands for the wheels joints.

CheckGoal2D

Check if wheeled robot has reached goal

Inputs
  • execIn (execution): The input execution.

  • currentPosition (vectord[3]): Current position of the robot (recommended to use Get Prim Local to World Transform node).

  • currentOrientation (quatd[4]): Current rotation of the robot as a quaternion (recommended to use Get Prim Local to World Transform node).

  • target (double[3]): Target position and orientation. Default to [0, 0, 0].

  • targetChanged (bool): Target position/orientation has changed. Default to False.

  • thresholds (double[2]): Position and orientation thresholds at target. Default to [0.1, 0.1].

Outputs
  • execOut (execution): The output execution.

  • reachedGoal (bool[]): Reached position and orientation goals.

StanleyControlPID

Drive to Target Steering

Inputs
  • execIn (execution): The input execution.

  • currentPosition (vectord[3]): Current position of the robot (recommended to use Get Prim Local to World Transform node).

  • currentOrientation (quatd[4]): Current rotation of the robot as a quaternion (recommended to use Get Prim Local to World Transform node).

  • currentSpeed (vectord[3]): Current linear velocity of the robot.

  • maxVelocity (double): Maximum linear velocity of the robot. Default to 1.5.

  • reachedGoal (bool[]): Position and orientation thresholds at target. Default to [False, False].

  • pathArrays (double[]): The path v, x, y, and yaw arrays.

  • target (double[3]): Target position and orientation. Default to [0, 0, 0].

  • targetChanged (bool): Target position/orientation has changed. Default to False.

  • wheelBase (double): Distance between the centers of the front and rear wheels. Default to 0.4132.

  • thresholds (double[2]): Position and orientation thresholds at target. Default to [0.1, 0.1].

  • drawPath (bool): Draw the provided path curve onto the stage. Default to False.

  • step (double): Step. Default to 0.16666666667.

  • gains (double[3]): control, velocity and steering gains. Default to [0.5, 0.1, 0.0872665].

Outputs
  • execOut (execution): The output execution.

  • linearVelocity (double): Current forward speed for robot drive.

  • angularVelocity (double): Current angular speed for robot drive.

AckermannController

Ackermann Controller

Inputs
  • execIn (execution): The input execution.

  • acceleration (double): Desired forward acceleration for the robot in m/s^2. Default to 1.0.

  • speed (double): Desired forward speed in m/s. Default to 1.0.

  • steeringAngle (double): Desired virtual angle in radians. Corresponds to the yaw of a virtual wheel located at the center of the front axle. By default it is positive for turning left and negative for turning right for front wheel drive. Default to 0.0.

  • currentLinearVelocity (vectord[3]): Current linear velocity of the robot in m/s. Default to [0.0, 0.0, 0.0].

  • wheelBase (double): Distance between the front and rear axles of the robot in meters. Default to 0.0.

  • trackWidth (double): Distance between the left and right rear wheels of the robot in meters. Default to 0.0.

  • turningWheelRadius (double): Radius of the front wheels of the robot in meters. Default to 0.0.

  • maxWheelVelocity (double): Maximum angular velocity of the robot wheel in rad/s. Default to 100000.

  • invertSteeringAngle (bool): Flips the sign of the steering angle, Set to true for rear wheel steering. Default to False.

  • useAcceleration (bool): Use acceleration as an input, Set to false to use speed as input instead. Default to False.

  • maxWheelRotation (double): Maximum angle of rotation for the front wheels in radians. Default to 6.28.

  • DT (double): Delta time for the simulation step.

Outputs
  • execOut (execution): The output execution.

  • leftWheelAngle (double): Angle for the left turning wheel in radians.

  • rightWheelAngle (double): Angle for the right turning wheel in radians.

  • wheelRotationVelocity (double): Angular velocity for the turning wheels in rad/s.

AckermannSteering

[‘NOTE: DEPRECATED as of Isaac Sim 4.1.0 in favour of OgnAckermannController’, ‘Ackermann Steering Geometry’]

Inputs
  • execIn (execution): The input execution.

  • acceleration (double): Desired forward acceleration for the robot in m/s^2.

  • speed (double): Desired forward speed in m/s.

  • steeringAngle (double): Desired virtual angle in radians. Corresponds to the yaw of a virtual wheel located at the center of the front axle. By default it is positive for turning left and negative for turning right for front wheel drive. Default to 0.0.

  • currentLinearVelocity (vectord[3]): Current linear velocity of the robot in m/s.

  • wheelBase (double): Distance between the front and rear axles of the robot in meters.

  • trackWidth (double): Distance between the left and right rear wheels of the robot in meters.

  • turningWheelRadius (double): Radius of the front wheels of the robot in meters.

  • maxWheelVelocity (double): Maximum angular velocity of the robot wheel in rad/s.

  • invertSteeringAngle (bool): Flips the sign of the steering angle, Set to true for rear wheel steering.

  • useAcceleration (bool): Use acceleration as an input, Set to false to use speed as input instead. Default to True.

  • maxWheelRotation (double): Maximum angle of rotation for the front wheels in radians.

  • DT (double): Delta time for the simulation step.

Outputs
  • execOut (execution): The output execution.

  • leftWheelAngle (double): Angle for the left turning wheel in radians.

  • rightWheelAngle (double): Angle for the right turning wheel in radians.

  • wheelRotationVelocity (double): Angular velocity for the turning wheels in rad/s.

DifferentialController

Differential Controller

Use the wheel radius and the distance between the wheels to calculate the desired wheels speed when given a desired vehicle speed.

Inputs
  • execIn (execution): The input execution.

  • wheelRadius (double): radius of the wheels. Default to 0.0.

  • wheelDistance (double): distance between the two wheels. Default to 0.0.

  • dt (double): delta time. Default to 0.0.

  • maxAcceleration (double): maximum linear acceleration of the robot for forward and reverse, 0.0 means not set. Default to 0.0.

  • maxDeceleration (double): maximum linear braking of the robot, 0.0 means not set. Default to 0.0.

  • maxAngularAcceleration (double): maximum angular acceleration of the robot, 0.0 means not set. Default to 0.0.

  • maxLinearSpeed (double): max linear speed allowed for vehicle, 0.0 means not set. Default to 0.0.

  • maxAngularSpeed (double): max angular speed allowed for vehicle, 0.0 means not set. Default to 0.0.

  • maxWheelSpeed (double): max wheel speed allowed, 0.0 means not set. Default to 0.0.

  • linearVelocity (double): desired linear velocity. Default to 0.0.

  • angularVelocity (double): desired rotation velocity. Default to 0.0.

Outputs
  • velocityCommand (double[]): velocity commands.