Wheeled Robots [omni.isaac.wheeled_robots]

Omnigraph Nodes

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 (bundle): prim for the robot’s articulation root.

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

  • usePath (bool): use prim path instead of prim bundles. 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.

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.

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

  • maxLinearSpeed (double): max linear speed allowed for vehicle.

  • maxAngularSpeed (double): max angular speed allowed for vehicle.

  • maxWheelSpeed (double): max wheel speed allowed.

  • linearVelocity (double): desired linear velocity.

  • angularVelocity (double): desired rotation velocity.

Outputs
  • positionCommand (double[]): position commands.

  • velocityCommand (double[]): velocity commands.

  • effortCommand (double[]): effort commands.

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.

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

  • velocityCommands ([‘float[3]’, ‘double[3]’]): velocity in x and y and rotation.

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

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

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

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

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

Outputs
  • jointPositionCommand (double[]): position commands for the wheel joints.

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

  • jointEffortCommand (double[]): effort commands for the wheels joints.