Isaac Sim [4.5] Husky Rotation Failure: Wheels forced straight during playback despite Orientation changes & correct settings

Note: For any Isaac Lab topics, please submit your topic to its GitHub repo (GitHub - isaac-sim/IsaacLab: Unified framework for robot learning built on NVIDIA Isaac Sim) following the instructions provided on Isaac Lab’s Contributing Guidelines (Contribution Guidelines — Isaac Lab Documentation).

Please provide all relevant details below before submitting your post. This will help the community provide more accurate and timely assistance. After submitting, you can check the appropriate boxes. Remember, you can always edit your post later to include additional information if needed.

Isaac Sim Version

4.5.0

code Repo:

Omniverse/Extension/[NetAI]GIST_Husky_IsaacSim_ROS at main · SmartX-Team/Omniverse

Reated to current issue’s Main Code :

Extension/[NetAI]GIST_Husky_IsaacSim_ROS/exts/gist.husky.isaacsim_ros/gist/husky/isaacsim_ros/ros_listeners.py

Operating System

Ubuntu 22.04

GPU Information

  • Model: RTXA6000
  • Driver Version: 535

Hello,

제목 없는 동영상 - Clipchamp로 제작 (2)

I am encountering a persistent issue controlling a custom URDF-based Husky robot in Isaac Sim [Your Version, e.g., 2024.1.1] using ROS2 Humble via the /cmd_vel topic. I would appreciate any insights or advice.

Problem Summary:

Environment: NVIDIA Isaac Sim [Your Version], ROS2 Humble, Custom URDF-based Husky model.
Control Method: OmniGraph setup via Python script, subscribing to /cmd_vel (geometry_msgs/Twist), using DifferentialController and IsaacArticulationController.
Symptoms:
The robot responds correctly to linear.x commands (moves forward/backward).
The robot completely fails to rotate in response to angular.z commands.
Core Issue 1: The Target Velocity property (Drive → Angular → Target Velocity) for individual wheel joints remains stuck at 0.0 in the Property panel, even when the IsaacArticulationController receives a valid velocityCommand array with different values for left and right wheels intended for rotation.
Core Issue 2: When the simulation is playing (Play mode), the wheels are actively forced into a straight-ahead position (likely the initial angle). This happens despite the fact that:
Individual wheel manipulation (e.g., changing orientation) is possible when paused.
The Transform → Orientation property of the wheel prims does change in real-time according to joystick input (visual/transform state is affected). However, the physics simulation seems to override this during playback, forcing the wheels straight.
Confirmed Working Aspects:

ROS2 Input: /cmd_vel topic publishing and subscription via ROS2SubscribeTwist node are working correctly.
OmniGraph Data Flow (Upstream):
BreakVector3 correctly extracts scalar linear.x and angular.z.
DifferentialController correctly receives inputs and calculates outputs:velocityCommand ([v_left, v_right]). Confirmed via OmniGraph editor that v_left and v_right have different values when a rotation command (angular.z != 0) is sent. (Parameters like wheelRadius=0.165, wheelDistance=0.555, maxLinearSpeed, maxAngularSpeed are set).
The [v_left, v_right] array is correctly reconstructed into a 4-element array [v_right, v_left, v_right, v_left] using ArrayIndex and ArrayInsertValue nodes.
This final 4-element array is correctly fed into IsaacArticulationController’s inputs:velocityCommand, and its values change in real-time based on joystick input (including different values for left/right sides).
IsaacArticulationController Inputs: inputs:positionCommand and inputs:effortCommand are confirmed to be empty or connected to empty arrays (size 0), ensuring they do not interfere with velocityCommand processing based on the suspected if/elif logic. inputs:robotPath and inputs:jointNames are set correctly.
Confirmed Joint Physics Settings (Applied via Python script):

UsdPhysics.DriveAPI: Explicitly set for all 4 wheel joints (PhysicsRevoluteJoint):
stiffness: 0.0 (Confirmed via Property panel).
damping: 100.0 (or other appropriate positive value, confirmed).
type: Tested with both “force” and “acceleration”, but the Target Velocity update failure persists in both cases. (Specify which one is currently set, e.g., “Currently set to ‘acceleration’”).
Joint Axis: Set to “X” for all joints (Correctness of “X” itself to be verified after rotation works, but the setting is applied).
Joint Limits: Lower/Upper limits are “Not Limited”.
Exclude From Articulation: Unchecked.
Joint-Wheel Mapping: Body 0 (base_link) and Body 1 (corresponding wheel prim) are correctly linked in each joint’s properties.
Collisions: Visual inspection shows no obvious initial interpenetration between wheel and body colliders.
PhysicsConstraint: Script-based check confirmed no explicit PhysicsConstraintAPI prims found under the Husky model.

2025-05-08144450-ezgif.com-video-to-gif-converter

Summary of Core Problem Symptoms (Consolidated):

Based on extensive debugging, the core conflicting symptoms are:

Despite all upstream OmniGraph logic appearing correct and delivering a valid velocityCommand (with different L/R values) to the IsaacArticulationController, and despite the joint DriveAPI properties (stiffness=0, damping>0, type tested as “force”/“acceleration”) being correctly set, the Target Velocity property on the joints remains fixed at 0.0.
Simultaneously, the Transform → Orientation of the wheel prims does react to the joystick input as intended.
However, when the simulation enters Play mode, the wheels are actively forced straight, overriding any orientation changes caused by the input. Manually trying to force an orientation change during playback also results in the rigid body (robot chassis) moving instead of just the wheel rotating relative to the chassis.
Request for Advice:

Given that we have seemingly ruled out common issues like incorrect DriveAPI parameters (Stiffness!=0), interfering positionCommand inputs, and explicit PhysicsConstraints, we are struggling to understand why:

The IsaacArticulationController is failing to update the Target Velocity attribute?
The physics simulation is actively forcing the wheels straight during playback, even overriding visual orientation changes.

dasdasdadasdad-ezgif.com-video-to-gif-converter

Could there be another mechanism, property, or bug within IsaacArticulationController or the PhysX integration in Isaac Sim 4.5 that could cause this behavior (failing to set Target Velocity AND actively forcing a straight orientation)?

I am looking for advice on what specific areas to investigate next to resolve this perplexing issue where rotation commands seem partially processed (affecting orientation) but ultimately fail at the physics execution level (forcing wheels straight, Target Velocity at 0).

Thank you for your time and assistance.