# liecasadi
[![liecasadi](https://github.com/ami-iit/liecasadi/actions/workflows/tests.yml/badge.svg)](https://github.com/ami-iit/liecasadi/actions/workflows/tests.yml)
`liecasadi` implements Lie groups operation written in CasADi, mainly directed to optimization problem formulation.
Inspired by [A micro Lie theory for state estimation in robotics](https://arxiv.org/pdf/1812.01537.pdf) and the library [Manif](https://github.com/artivis/manif).
## π Install
Create a [virtual environment](https://docs.python.org/3/library/venv.html#venv-def), if you prefer. For example:
```bash
pip install virtualenv
python3 -m venv your_virtual_env
source your_virtual_env/bin/activate
```
Inside the virtual environment, install the library from pip:
```bash
pip install liecasadi
```
If you want the last version:
```bash
pip install "liecasadi @ git+https://github.com/ami-iit/lie-casadi.git"
```
## Implemented Groups
| **Group** | Description |
| --------- | ------------------ |
| SO3 | 3D Rotations |
| SE3 | 3D Rigid Transform |
### π Operations
Being:
- $X, Y \in SO3, \ SE3$
- $w \in \text{SO3Tangent}, \ \text{SE3Tangent}$
- $v \in \mathbb{R}^3$
| Operation | | Code |
| :------------------ | :-----------------------------------: | :-----------: |
| Inverse | $X^{-1}$ | `X.inverse()` |
| Composition | $X \circ Y$ | `X*Y` |
| Exponential | $\text{exp}(w)$ | `phi.exp() ` |
| Act on vector | $X \circ v$ | `X.act(v)` |
| Logarithm | $\text{log}(X)$ | `X.log()` |
| Manifold right plus | $X \oplus w = X \circ \text{exp}(w)$ | `X + phi` |
| Manifold left plus | $w \oplus X = \text{exp}(w) \circ X$ | `phi + X` |
| Manifold minus | $X-Y = \text{log}(Y^{-1} \circ X)$ | `X-Y` |
## π¦ΈββοΈ Example
```python
from liecasadi import SE3, SO3, SE3Tangent, SO3Tangent
# Random quaternion + normalization
quat = (np.random.rand(4) - 0.5) * 5
quat = quat / np.linalg.norm(quat)
# Random vector
vector3d = (np.random.rand(3) - 0.5) * 2 * np.pi
# Create SO3 object
rotation = SO3(quat)
# Create Identity
identity = SO3.Identity()
# Create SO3Tangent object
tangent = SO3Tangent(vector3d)
# Random translation vector
pos = (np.random.rand(3) - 0.5) * 5
# Create SE3 object
transform = SE3(pos=pos, xyzw=quat)
# Random vector
vector6d = (np.random.rand(3) - 0.5) * 5
# Create SE3Tangent object
tangent = SO3Tangent(vector6d)
```
### Dual Quaternion example
```python
from liecasadi import SE3, DualQuaternion
from numpy import np
# orientation quaternion generation
quat1 = (np.random.rand(4) - 0.5) * 5
quat1 = quat1 / np.linalg.norm(quat1)
quat2 = (np.random.rand(4) - 0.5) * 5
quat2 = quat2 / np.linalg.norm(quat2)
# translation vector generation
pos1 = (np.random.rand(3) - 0.5) * 5
pos2 = (np.random.rand(3) - 0.5) * 5
dual_quaternion1 = DualQuaternion(quat1, pos1)
dual_quaternion2 = DualQuaternion(quat2, pos2)
# from a homogenous matrix
# (using liecasadi.SE3 to generate the corresponding homogenous matrix)
H = SE3.from_position_quaternion(pos, quat).as_matrix()
dual_quaternion1 = DualQuaternion.from_matrix(H)
# Concatenation of rigid transforms
q1xq2 = dual_quaternion1 * dual_quaternion2
# to homogeneous matrix
print(q1xq2.as_matrix())
# obtain translation
print(q1xq2.translation())
# obtain rotation
print(q1xq2.rotation().as_matrix())
# transform a point
point = np.random.randn(3,1)
transformed_point = dual_quaternion1.transform_point(point)
# create an identity dual quaternion
I = DualQuaternion.Identity()
```
## π¦ΈββοΈ Contributing
**liecasadi** is an open-source project. Contributions are very welcome!
Open an issue with your feature request or if you spot a bug. Then, you can also proceed with a Pull-requests! :rocket:
Raw data
{
"_id": null,
"home_page": "",
"name": "liecasadi",
"maintainer": "",
"docs_url": null,
"requires_python": ">=3.8",
"maintainer_email": "",
"keywords": "robotics,automatic-differentiation,optimization,casadi,lie-groups,manifolds",
"author": "Giuseppe L'Erario",
"author_email": "gl.giuseppelerario@gmail.com",
"download_url": "https://files.pythonhosted.org/packages/99/71/cfeaa87e73c818f1028d7e238d10d8e8e60172ff4bed30ba053fd54a9410/liecasadi-0.0.6.tar.gz",
"platform": null,
"description": "# liecasadi\n\n[![liecasadi](https://github.com/ami-iit/liecasadi/actions/workflows/tests.yml/badge.svg)](https://github.com/ami-iit/liecasadi/actions/workflows/tests.yml)\n\n`liecasadi` implements Lie groups operation written in CasADi, mainly directed to optimization problem formulation.\n\nInspired by [A micro Lie theory for state estimation in robotics](https://arxiv.org/pdf/1812.01537.pdf) and the library [Manif](https://github.com/artivis/manif).\n\n## \ud83d\udc0d Install\n\nCreate a [virtual environment](https://docs.python.org/3/library/venv.html#venv-def), if you prefer. For example:\n\n```bash\npip install virtualenv\npython3 -m venv your_virtual_env\nsource your_virtual_env/bin/activate\n```\n\nInside the virtual environment, install the library from pip:\n\n```bash\npip install liecasadi\n```\n\nIf you want the last version:\n\n```bash\npip install \"liecasadi @ git+https://github.com/ami-iit/lie-casadi.git\"\n```\n\n## Implemented Groups\n\n| **Group** | Description |\n| --------- | ------------------ |\n| SO3 | 3D Rotations |\n| SE3 | 3D Rigid Transform |\n\n### \ud83d\ude80 Operations\n\nBeing:\n\n- $X, Y \\in SO3, \\ SE3$\n\n- $w \\in \\text{SO3Tangent}, \\ \\text{SE3Tangent}$\n\n- $v \\in \\mathbb{R}^3$\n\n| Operation | | Code |\n| :------------------ | :-----------------------------------: | :-----------: |\n| Inverse | $X^{-1}$ | `X.inverse()` |\n| Composition | $X \\circ Y$ | `X*Y` |\n| Exponential | $\\text{exp}(w)$ | `phi.exp() ` |\n| Act on vector | $X \\circ v$ | `X.act(v)` |\n| Logarithm | $\\text{log}(X)$ | `X.log()` |\n| Manifold right plus | $X \\oplus w = X \\circ \\text{exp}(w)$ | `X + phi` |\n| Manifold left plus | $w \\oplus X = \\text{exp}(w) \\circ X$ | `phi + X` |\n| Manifold minus | $X-Y = \\text{log}(Y^{-1} \\circ X)$ | `X-Y` |\n\n## \ud83e\uddb8\u200d\u2642\ufe0f Example\n\n```python\nfrom liecasadi import SE3, SO3, SE3Tangent, SO3Tangent\n\n# Random quaternion + normalization\nquat = (np.random.rand(4) - 0.5) * 5\nquat = quat / np.linalg.norm(quat)\n# Random vector\nvector3d = (np.random.rand(3) - 0.5) * 2 * np.pi\n\n# Create SO3 object\nrotation = SO3(quat)\n\n# Create Identity\nidentity = SO3.Identity()\n\n# Create SO3Tangent object\ntangent = SO3Tangent(vector3d)\n\n# Random translation vector\npos = (np.random.rand(3) - 0.5) * 5\n\n# Create SE3 object\ntransform = SE3(pos=pos, xyzw=quat)\n\n# Random vector\nvector6d = (np.random.rand(3) - 0.5) * 5\n\n# Create SE3Tangent object\ntangent = SO3Tangent(vector6d)\n```\n\n### Dual Quaternion example\n\n```python\nfrom liecasadi import SE3, DualQuaternion\nfrom numpy import np\n\n# orientation quaternion generation\nquat1 = (np.random.rand(4) - 0.5) * 5\nquat1 = quat1 / np.linalg.norm(quat1)\nquat2 = (np.random.rand(4) - 0.5) * 5\nquat2 = quat2 / np.linalg.norm(quat2)\n\n# translation vector generation\npos1 = (np.random.rand(3) - 0.5) * 5\npos2 = (np.random.rand(3) - 0.5) * 5\n\ndual_quaternion1 = DualQuaternion(quat1, pos1)\ndual_quaternion2 = DualQuaternion(quat2, pos2)\n\n# from a homogenous matrix\n# (using liecasadi.SE3 to generate the corresponding homogenous matrix)\nH = SE3.from_position_quaternion(pos, quat).as_matrix()\ndual_quaternion1 = DualQuaternion.from_matrix(H)\n\n# Concatenation of rigid transforms\nq1xq2 = dual_quaternion1 * dual_quaternion2\n\n# to homogeneous matrix\nprint(q1xq2.as_matrix())\n\n# obtain translation\nprint(q1xq2.translation())\n\n# obtain rotation\nprint(q1xq2.rotation().as_matrix())\n\n# transform a point\npoint = np.random.randn(3,1)\ntransformed_point = dual_quaternion1.transform_point(point)\n\n# create an identity dual quaternion\nI = DualQuaternion.Identity()\n```\n\n## \ud83e\uddb8\u200d\u2642\ufe0f Contributing\n\n**liecasadi** is an open-source project. Contributions are very welcome!\n\nOpen an issue with your feature request or if you spot a bug. Then, you can also proceed with a Pull-requests! :rocket:\n",
"bugtrack_url": null,
"license": "",
"summary": "Rigid transform using Lie groups, written in CasADi!",
"version": "0.0.6",
"project_urls": null,
"split_keywords": [
"robotics",
"automatic-differentiation",
"optimization",
"casadi",
"lie-groups",
"manifolds"
],
"urls": [
{
"comment_text": "",
"digests": {
"blake2b_256": "1210bc6c7e74ed6071c41220cf080ee9148e3bb84e1fcce8cae1f380d0fac6a8",
"md5": "d2dbe59b6ddc293edf5c3c4d06fc460f",
"sha256": "f3e444ab2178c84cecd9ee3d238872abdee7eb22778a10f709b00885513d899d"
},
"downloads": -1,
"filename": "liecasadi-0.0.6-py3-none-any.whl",
"has_sig": false,
"md5_digest": "d2dbe59b6ddc293edf5c3c4d06fc460f",
"packagetype": "bdist_wheel",
"python_version": "py3",
"requires_python": ">=3.8",
"size": 10586,
"upload_time": "2024-01-16T12:02:29",
"upload_time_iso_8601": "2024-01-16T12:02:29.888450Z",
"url": "https://files.pythonhosted.org/packages/12/10/bc6c7e74ed6071c41220cf080ee9148e3bb84e1fcce8cae1f380d0fac6a8/liecasadi-0.0.6-py3-none-any.whl",
"yanked": false,
"yanked_reason": null
},
{
"comment_text": "",
"digests": {
"blake2b_256": "9971cfeaa87e73c818f1028d7e238d10d8e8e60172ff4bed30ba053fd54a9410",
"md5": "bad14b09afa6cc8ab561e3131797a460",
"sha256": "27fe534ea96dd4dffcecfdfb65ae484e09b45e7691cb8e2bf6d7fc62edd33eee"
},
"downloads": -1,
"filename": "liecasadi-0.0.6.tar.gz",
"has_sig": false,
"md5_digest": "bad14b09afa6cc8ab561e3131797a460",
"packagetype": "sdist",
"python_version": "source",
"requires_python": ">=3.8",
"size": 14696,
"upload_time": "2024-01-16T12:02:31",
"upload_time_iso_8601": "2024-01-16T12:02:31.518763Z",
"url": "https://files.pythonhosted.org/packages/99/71/cfeaa87e73c818f1028d7e238d10d8e8e60172ff4bed30ba053fd54a9410/liecasadi-0.0.6.tar.gz",
"yanked": false,
"yanked_reason": null
}
],
"upload_time": "2024-01-16 12:02:31",
"github": false,
"gitlab": false,
"bitbucket": false,
"codeberg": false,
"lcname": "liecasadi"
}