Simulation disrespecting joint limits

Isaac Sim 2023.1.1
I have a robot with 24 revolute joints. Certain joint positions cause other joints to move outside their limits.
Example console warning:[Warning] [omni.isaac.articulation_inspector.extension] value 0.22296705842018127 doesn’t respect the dof index 16 joint limits

I believe I have these set up as hard limits( real-world robot has servo limits). They follow the description in the physx documentation: Limits may be either hard or soft . When a hard limit is reached, relative motion will simply stop dead if the limit is configured with zero restitution, or bounce if the restitution is non-zero.
By default, limits are hard and without restitution, so when the joint reaches a limit motion will simply stop

Break force and torque are both 3402823466385288598117041834845 and there is no warning about joint breakage.

Any clues as to how I can get the simulation to enforce/obey these joint limits?

Hi @mccunnj - I don’t think the warning above indicates a simulation issue. This is a warning triggered by the articulation inspector if the user sets either a dof position or dof position drive target that is not within the dofs position limit. You can check the source code, too, this line:

    def _on_controller_value_changed(self, name, model, id):
        """Callback for when a Joint Controller Slider is modified.

        Args:
            name (string): ui.Label.text
            model (ui.AbstractValueModel): ui.FloatField model
            id (int): Index of DOF
        """
        # carb.log_warn(f"{name}, {id}, {model.get_value_as_float()}")
        if self.num_dof is not None:

            if id > -1 and id < self.num_dof:
                val = model.get_value_as_float()

                if "pos" in name.lower():
                    name = "pos"
                    if val >= self.lower_limits[id] and val <= self.upper_limits[id]:
                        self.positions[id] = val
                    else:
                        carb.log_warn("value {} doesn't respect the dof index {} joint limits".format(val, id))

@philipp.reist ,
I think this warning also comes up when refreshing the joint values in the articulation viewer. The joint in question was not set, but the simulation pushed the joint outside of its limits when moving a different joint up the articulation chain. The out of limit joint is connected to a link that is a foot that is getting pushed against the ground.

Ok thank you for clarifying.

Then I suspect that the solver cannot satisfy the constraint in the iterations given. Can you please try bumping position iterations on the articulation?

1 Like

@philipp.reist ,
In Isaac Sim, I doubled it until I got it to work and ended up with 255 :( . I had to boot the stiffness and damping by a lot too! I saved the usd. To carry this over to Isaac Gym, I had to add
position_iteration_counts_tensor = torch.full((self._num_envs,), 255, device=self._device)
self._pinkys.set_solver_position_iteration_counts(position_iteration_counts_tensor)

after I added my articulationView to the scene.

Thanks for pointing me in the right direction!

255 is the max and should not be needed, frowny face indeed :( If you are able to share the USD I can have a look if you want.

Is there a preferred way to share? Here is a g drive link pinkySnap.usd - Google Drive

Ok the simulation looks ok, and I reduced the iterations to 32,1 - no point going too high with velocity iterations for TGS.

How are you evaluating whether the joint limit is violated - it was not obvious to me how and where it is violated.

I was using the gain tuner to randomize positions and the ankle joints were bending out of limits. I just increased the ankle masses from .001 to .1 and that helped too. I got 128,1 to work
I just tried 32,1 and it still violates limits. I can see it visually when it goes outside its 90-degree range.

The goal is to train this to walk using Isaac Gym. In the calculating metrics section, I have this:

def joint_limit_check(prims, lower_limits, upper_limits, targets):
joint_positions = prims.get_joint_positions()
# print(“joint_POS:”, joint_positions)

    # Check if joint positions exceed the upper limits
    exceeds_upper_limits = joint_positions > upper_limits
    # Check if joint positions fall below the lower limits
    falls_below_lower_limits = joint_positions < lower_limits
    # Combine the two conditions to find joints that violate the limits
    violates_limits = exceeds_upper_limits | falls_below_lower_limits
    # Sum up the violations along the joint dimension to see if any environment has violations
    envs_with_violations = torch.sum(violates_limits, dim=1) > 0
    # Print the indices of environments where violations occur
    # print("Indices of environments with violations:", torch.nonzero(envs_with_violations))
    # Find the indices of joints that are out of limits for each environment
    out_of_limits_indices = torch.nonzero(violates_limits, as_tuple=False)
    print("OOL indices:", out_of_limits_indices)
    #Print the indices of environments, the joint indices, positions, and limits that are out of limits
    for env_index in range(out_of_limits_indices.shape[0]):
        env_idx, joint_idx = out_of_limits_indices[env_index]
        joint_position = joint_positions[env_idx, joint_idx]
        lower_limit = lower_limits[joint_idx]
        upper_limit = upper_limits[joint_idx]
        joint_name = prims.dof_names[joint_idx]
        print(f"Environment {env_idx}: {joint_name} is out of limits. Position: {joint_position}, Lower Limit: {lower_limit}, Upper Limit: {upper_limit}")
        print(f"Target: {targets[env_idx][joint_idx]}, Effort: {prims.get_measured_joint_efforts()[env_idx][joint_idx]}")
        print(f"Forces on target joint: {prims.get_measured_joint_forces()[env_idx][joint_idx]}")

So you get the violations when training? What is your action space? Torques or joint target positions?

I get only minor violations when training now with these params in my .yaml:
Pinky:
# -1 to use default values
override_usd_defaults: True
enable_self_collisions: True
enable_gyroscopic_forces: True
# also in stage params
# per-actor
solver_position_iteration_count: 128
solver_velocity_iteration_count: 1
sleep_threshold: 0.005
stabilization_threshold: 0.001
# per-body
density: -1
max_depenetration_velocity: 100.0
# per-shape
contact_offset: 0.02
rest_offset: 0.001

My action space is 24 actions -1 to 1. Actions are then scaled to the joint min/max.
# Compute targets from the actions
# Scale actions from range [-1, 1] to range [0, 1] for interpolation
scaled_actions = (actions + 1) / 2
# Interpolate scaled actions to get values between lower and upper limits
interpolated_values = self.pinky_dof_lower_limits + scaled_actions * ( self.pinky_dof_upper_limits - self.pinky_dof_lower_limits)
self.current_targets[:] = tensor_clamp(
interpolated_values, self.pinky_dof_lower_limits, self.pinky_dof_upper_limits
)

I am using joint target positions.

apply actions to all of the environments

    indices = torch.arange(self._pinkys.count, dtype=torch.int32, device=self._device)
    self._pinkys.set_joint_position_targets(self.current_targets, indices)

Are you enforcing actuator force and velocity limits? I would suspect that there is some issue with the actions being too strong/wild during initial training, causing the limits to be violated.

The number of iterations are still way too high; lower iterations would give you much better perf.

I have used set_drive to sed max efforts to

efforts

    self.effort_knee = 1.471 # Nm from 15kgf*cm
    self.effort_ankle = 1.372931 # Nm from 14kgf*cm
    self.effort_hip = 0.3526 # Nm from 3.6kg/cm

and max joint velocities are set in the raw USD properties from the URDF. All are around mid 200 deg/sec

Is it possible for you to share a repro that includes some of the action sequences that lead to the joint limit violations? E.g. by recording the inputs and then replaying them in a script?

I’m not sure how to do that. I’ll look into it. From isaac sim or gym?

Ideally from IsaacSim. I think if you record the actions applied at each step, store and then replay from e.g. a numpy pickle (?) that would work.

image
Working on a script. But for now, here, I set the knee to -45 and the ankle stayed within bounds. But when I set the target position of the ankle to -45, it flops beyond its limit to a position of 19.9…
Here is the result with a solver count of 128:
image
This it doesn’t reach its target, but that is more similar to the real robot.

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.