add isaac sim 2023.1.1 partial support

This commit is contained in:
Balakumar Sundaralingam
2024-03-22 19:41:00 -07:00
parent b1f63e8778
commit b481ee201a
5 changed files with 35 additions and 24 deletions

View File

@@ -437,7 +437,7 @@ class SelfCollisionKinematicsConfig:
checks_per_thread: int = 32
@dataclass(frozen=True)
@dataclass
class CudaRobotModelState:
"""Dataclass that stores kinematics information."""

View File

@@ -25,13 +25,13 @@ from curobo.util.torch_utils import get_torch_jit_decorator
# kernel for l-bfgs:
@get_torch_jit_decorator()
@get_torch_jit_decorator(only_valid_for_compile=True)
def jit_lbfgs_compute_step_direction(
alpha_buffer,
rho_buffer,
y_buffer,
s_buffer,
grad_q,
alpha_buffer: torch.Tensor,
rho_buffer: torch.Tensor,
y_buffer: torch.Tensor,
s_buffer: torch.Tensor,
grad_q: torch.Tensor,
m: int,
epsilon: float,
stable_mode: bool = True,

View File

@@ -224,15 +224,12 @@ class PoseCost(CostBase, PoseCostConfig):
run_weight = self.run_weight
active_steps = math.floor(self._horizon * run_tstep_fraction)
self.initialize_run_weight_vec(self._horizon)
self._run_weight_vec[:, :active_steps] = 0
self._run_weight_vec[:, active_steps:-1] = run_weight
def update_batch_size(self, batch_size, horizon):
if batch_size != self._batch_size or horizon != self._horizon:
# print(self.weight)
# print(batch_size, horizon, self._batch_size, self._horizon)
# batch_size = b*h
self.out_distance = torch.zeros(
(batch_size, horizon), device=self.tensor_args.device, dtype=self.tensor_args.dtype
)
@@ -265,16 +262,21 @@ class PoseCost(CostBase, PoseCostConfig):
device=self.tensor_args.device,
dtype=self.tensor_args.dtype,
)
if self._run_weight_vec is None or self._run_weight_vec.shape[1] != horizon:
self._run_weight_vec = torch.ones(
(1, horizon), device=self.tensor_args.device, dtype=self.tensor_args.dtype
)
self.initialize_run_weight_vec(horizon)
if self.terminal and self.run_weight is not None and horizon > 1:
self._run_weight_vec[:, :-1] = self.run_weight
self._batch_size = batch_size
self._horizon = horizon
def initialize_run_weight_vec(self, horizon: Optional[int] = None):
if horizon is None:
horizon = self._horizon
if self._run_weight_vec is None or self._run_weight_vec.shape[1] != horizon:
self._run_weight_vec = torch.ones(
(1, horizon), device=self.tensor_args.device, dtype=self.tensor_args.dtype
)
@property
def goalset_index_buffer(self):
return self.out_idx