adam.casadi.casadi_like#
Classes#
Wrapper class for CasADi SX/DM with ArrayLike ops. |
|
ArrayLikeFactory for CasADi. Drops batch dims (>2) since CasADi is 2-D only. |
|
CasADi backend for SpatialMath. Keeps the same high-level API. |
Module Contents#
- class adam.casadi.casadi_like.CasadiLike[source]#
Bases:
adam.core.spatial_math.ArrayLikeWrapper class for CasADi SX/DM with ArrayLike ops.
- __matmul__(other: CasadiLike) CasadiLike[source]#
- __rmatmul__(other: CasadiLike) CasadiLike[source]#
- __mul__(other: CasadiLike) CasadiLike[source]#
- __rmul__(other: CasadiLike) CasadiLike[source]#
- __truediv__(other: CasadiLike) CasadiLike[source]#
- __add__(other: CasadiLike) CasadiLike[source]#
- __radd__(other: CasadiLike) CasadiLike[source]#
- __sub__(other: CasadiLike) CasadiLike[source]#
- __rsub__(other: CasadiLike) CasadiLike[source]#
- __neg__() CasadiLike[source]#
- __getitem__(idx) CasadiLike[source]#
- property T: CasadiLike[source]#
Transpose of the array
- Type:
Returns
- class adam.casadi.casadi_like.CasadiLikeFactory(xp: casadi.SX | casadi.DM | None = None)[source]#
Bases:
adam.core.spatial_math.ArrayLikeFactoryArrayLikeFactory for CasADi. Drops batch dims (>2) since CasADi is 2-D only.
- zeros(*x: numpy.typing.ArrayLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – matrix dimension
- Returns:
zero matrix of dimension x
- Return type:
npt.ArrayLike
- eye(x: numpy.typing.ArrayLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – matrix dimension
- Returns:
identity matrix of dimension x
- Return type:
npt.ArrayLike
- asarray(x) CasadiLike[source]#
Convert input to a CasadiLike array.
This method handles various input types and converts them to CasadiLike objects using appropriate CasADi operations for concatenation and array construction.
- Parameters:
x – Input to convert. Can be:
list (- Empty) – Returns empty CasadiLike array
objects (- List of CasADi) – Horizontally concatenated
lists/tuples (- List of) – Creates 2D array with vertical and horizontal concatenation
numbers (- Numbers or lists of) – Direct conversion to CasadiLike
- Returns:
A CasadiLike object wrapping the converted input.
- Return type:
Examples
Empty list [] -> CasadiLike with empty array
[sx1, sx2] -> CasadiLike with horizontally concatenated SX objects
[[1, 2], [3, 4]] -> CasadiLike with 2x2 matrix
5 or [1, 2, 3] -> CasadiLike with direct conversion
- zeros_like(x: CasadiLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – array
- Returns:
one array with the same shape as x
- Return type:
npt.ArrayLike
- ones_like(x: CasadiLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – array
- Returns:
one array with the same shape as x
- Return type:
npt.ArrayLike
- tile(x: CasadiLike, reps: tuple) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – input array
reps (tuple) – repetition factors for each dimension
- Returns:
tiled array
- Return type:
npt.ArrayLike
- class adam.casadi.casadi_like.SpatialMath(spec=None)[source]#
Bases:
adam.core.spatial_math.SpatialMathCasADi backend for SpatialMath. Keeps the same high-level API.
- static sin(x: CasadiLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – angle value
- Returns:
sin value of x
- Return type:
npt.ArrayLike
- static cos(x: CasadiLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – angle value
- Returns:
cos value of angle x
- Return type:
npt.ArrayLike
- static skew(x: CasadiLike | numpy.typing.ArrayLike) CasadiLike[source]#
- static outer(x: CasadiLike, y: CasadiLike) CasadiLike[source]#
- static vertcat(*x: CasadiLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – elements
- Returns:
vertical concatenation of elements x
- Return type:
npt.ArrayLike
- static horzcat(*x: CasadiLike) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – elements
- Returns:
horizontal concatenation of elements x
- Return type:
npt.ArrayLike
- static stack(x: Sequence[CasadiLike], axis: int = 0) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – elements
axis (int) – axis along which to stack
- Returns:
stacked elements x along axis
- Return type:
npt.ArrayLike
- static concatenate(x: Sequence[CasadiLike], axis: int = 0) CasadiLike[source]#
Concatenate a sequence of CasadiLike objects along a specified axis.
This function provides flexible concatenation behavior with special handling for common use cases in CasADi operations.
- Parameters:
x (Sequence[CasadiLike]) – Sequence of CasadiLike objects to concatenate
axis (int, optional) – Axis along which to concatenate. Defaults to 0. - 0 or -2: Vertical concatenation (stack rows) - 1 or -1: Horizontal concatenation (stack columns)
- Returns:
The concatenated result
- Return type:
- Raises:
NotImplementedError – If axis is not in {-2, -1, 0, 1}
- Special Cases:
When axis=-1 and exactly 2 column vectors are provided, they are
vertically stacked to create a longer column vector - For horizontal concatenation (axis=1 or -1), if arrays don’t have matching row dimensions, the function attempts to reshape them: * 1D arrays are reshaped to column vectors * Row vectors (1xn) are transposed to column vectors * Other shapes are kept as-is and stacked vertically
Note
The function uses CasADi’s vertcat and horzcat functions internally for the actual concatenation operations.
- static swapaxes(x: CasadiLike, axis1: int, axis2: int) CasadiLike[source]#
- tile(x: CasadiLike, reps: tuple) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – input array
reps (tuple) – repetition factors for each dimension
- Returns:
tiled array
- Return type:
npt.ArrayLike
- transpose(x: CasadiLike, dims: tuple) CasadiLike[source]#
- Parameters:
x (npt.ArrayLike) – input array
dims (tuple) – permutation of dimensions
- Returns:
transposed array
- Return type:
npt.ArrayLike
- static expand_dims(x: CasadiLike, axis: int) CasadiLike[source]#
Expand dimensions of a CasADi array.
- Parameters:
x – Input array (CasadiLike)
axis – Position where new axis is to be inserted
- Returns:
Array with expanded dimensions
- Return type:
- static inv(x: CasadiLike) CasadiLike[source]#
Matrix inversion for CasADi.
- Parameters:
x – Matrix to invert (CasadiLike)
- Returns:
Inverse of x
- Return type:
- static solve(A: CasadiLike, B: CasadiLike) CasadiLike[source]#
Solve linear system Ax = B for x using CasADi.
- Parameters:
A – Coefficient matrix (CasadiLike)
B – Right-hand side vector or matrix (CasadiLike)
- Returns:
Solution x
- Return type:
- static mtimes(A: CasadiLike, B: CasadiLike) CasadiLike[source]#
Matrix-matrix multiplication for CasADi.
- Parameters:
A – First matrix (CasadiLike)
B – Second matrix (CasadiLike)
- Returns:
Result of A @ B
- Return type:
- static mxv(m: CasadiLike, v: CasadiLike) CasadiLike[source]#
Matrix-vector multiplication for CasADi.
- Parameters:
m – Matrix (CasadiLike)
v – Vector (CasadiLike)
- Returns:
Returns a column vector (n,1).
- Return type:
- static vxs(v: CasadiLike, c: CasadiLike) CasadiLike[source]#
Vector times scalar multiplication for CasADi.
- Parameters:
v – Vector (CasadiLike)
c – Scalar (CasadiLike)
- Returns:
Result of vector times scalar
- Return type: