Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
29 changes: 29 additions & 0 deletions .github/workflows/docs.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,29 @@
name: Generate Python Documentation

on: [pull_request]

jobs:
build-docs:
runs-on: ubuntu-22.04
steps:
- name: Checkout Repository
uses: actions/checkout@v3

- name: Set up Python 3.10
uses: actions/setup-python@v4
with:
python-version: '3.10'

- name: Install Dependencies
run: |
python -m pip install --upgrade pip
pip install .[dev,pollen]

- name: Generate Documentation
run: pdoc reachy2_symbolic_ik --output-dir docs --logo "https://pollen-robotics.github.io/reachy2-sdk/pollen_logo.png" --logo-link "https://www.pollen-robotics.com" --docformat google

- name: Archive Documentation
uses: actions/upload-artifact@v3
with:
name: documentation
path: docs/
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ instance/

# Sphinx documentation
docs/_build/
docs/

# PyBuilder
.pybuilder/
Expand Down
41 changes: 41 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -43,8 +43,20 @@ Learn the core concepts behind our symbolic inverse kinematics approach (French
</a>
</p>

To better understand the frame conventions used in the IK, the following figure illustrates the torso frame and the end-effector frame:

<table>
<tr>
<td align="center">
<img src="./docs/img/reachy_frames1.png" alt="Top Grasp Demo" width="100%">
</td>
<td align="center">
<img src="./docs/img/reachy_frames2.png" alt="Null Space Visualization" width="100%">
</td>
</tr>
</table>

For more detailed explanations, benchmarks, and discussions on specific issues, you can refer to our Notion page: [Notion IK Documentation](https://www.notion.so/pollen-robotics/Symbol-IK-27a420dfc4404c52a02fe93c10142229) (in French).

## Install

Expand Down Expand Up @@ -185,6 +197,16 @@ or
$ python3 -m pytest -m cicd
```

## Documentation

The Documentation can be generated locally via pdoc with:

```console
pdoc reachy2_symbolic_ik --output-dir docs --logo "https://pollen-robotics.github.io/reachy2-sdk/pollen_logo.png" --logo-link "https://www.pollen-robotics.com" --docformat google
```

*You maybe have to install pdoc first by running* `pip install pdoc`.

## URDF

A URDF file is provided in 'src/config_files/reachy2.urdf'. This file is used if the user does not provide a URDF file when initializing the ControlIK class.
Expand All @@ -195,6 +217,25 @@ To regenerate the URDF file, you can use the following command from the root of
$ xacro ../../reachy_ws/src/reachy2_core/reachy_description/urdf/reachy.urdf.xacro "use_fake_hardware:=true" > src/config_files/reachy2.urdf
```

## Contributing

We welcome contributions! Here’s how you can help:

- **Report Issues**: Found a bug or have a feature request? Open an issue here.

- **Fix Bugs & Add Features**: Check out our open issues tagged as good first issue or help wanted.

### Some Key Issues to Tackle
- [Optimize control compute time](https://github.com/pollen-robotics/reachy2_symbolic_ik/issues/94)
- [Improve pytest tests](https://github.com/pollen-robotics/reachy2_symbolic_ik/issues/93)

Make sure your code:
- Follows the Black code style.
- Respects the isort import order.
- Passes mypy type checking.
- Passes all unit tests (pytest).

## License

This project is licensed under the [Apache 2.0 License](LICENSE). See the LICENSE file for details.

3 changes: 3 additions & 0 deletions docs/img/reachy_frames1.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
3 changes: 3 additions & 0 deletions docs/img/reachy_frames2.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
1 change: 1 addition & 0 deletions setup.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ dev = black==23.12.1
coverage==7.3.2
mypy==1.8.0
isort==5.13.2
pdoc==14.4.0
matplotlib==3.5.1
types-protobuf==5.27.0.20240626

Expand Down
23 changes: 17 additions & 6 deletions src/reachy2_symbolic_ik/control_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,17 @@ def __init__( # noqa: C901
reachy_model: str = "full_kit",
is_dvt: bool = False,
) -> None:
"""
Args:
current_joints: list of the current joints of the arms (rad)
current_pose: list of the current pose of the arms (4x4 homogeneous matrix)
logger
urdf: URDF string (optional)
urdf_path: path to the URDF file (optional)
reachy_model: full_kit, starter_kit_right, starter_kit_left, mini (default: full_kit)
is_dvt: True if the robot is a DVT or PVT
"""

self.symbolic_ik_solver = {}
self.last_call_t = {}
self.call_timeout = 0.2
Expand Down Expand Up @@ -176,14 +187,14 @@ def symbolic_inverse_kinematics( # noqa: C901
name: r_arm or l_arm
M: 4x4 homogeneous matrix of the goal pose
control_type: continuous or discrete
current_joints: current joints of the arm
current_joints: current joints of the arm (rad)
constrained_mode: unconstrained or low_elbow
current_pose: current pose of the arm
d_theta_max: maximum angle difference between two consecutive theta
preferred_theta: preferred theta of the right arm
current_pose: current pose of the arm (4x4 homogeneous matrix)
d_theta_max: maximum angle difference between two consecutive theta (rad)
preferred_theta: preferred theta of the right arm (rad)
Returns:
ik_joints: list of the joints angles
is_reachable: True if the goal pose is reachable
ik_joints: list of the joints angles (rad)
is_reachable: boolean
state: if not reachable, the reason why
"""
# print(M[:3, :3])
Expand Down
32 changes: 31 additions & 1 deletion src/reachy2_symbolic_ik/symbolic_ik.py
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,28 @@ def __init__(
singularity_offset: float = 0.03,
singularity_limit_coeff: float = 1.0,
) -> None:
"""Create a symbolic IK object
Args:
arm (str): 'r_arm' or 'l_arm'
ik_parameters (dict[str, Any]): dictionnary with the following keys
- r_shoulder_position (np.array): shoulder position of the right arm (meters)
- r_shoulder_orientation (list): shoulder orientation of the right arm (degrees)
- r_upper_arm_size (np.float64): upper arm size of the right arm (meters)
- r_forearm_size (np.float64): forearm size of the right arm (meters)
- r_tip_position (np.array): right tip position in wrist frame (meters)
- l_shoulder_position (np.array): shoulder position of the left arm (meters)
- l_shoulder_orientation (list): shoulder orientation of the left arm (degrees)
- l_upper_arm_size (np.float64): upper arm size of the left arm (meters)
- l_forearm_size (np.float64): forearm size of the left arm (meters)
- l_tip_position (np.array): left tip position in wrist frame (meters)
elbow_limit (int) : elbow limit in degrees
wrist_limit (np.float64): wrist limit in degrees
projection_margin (float): margin for the projection of the goal position on the reachable sphere
backward_limit (float): limit for the wrist and the tip to go backward
normal_vector_margin (float): margin for the normal vector of the wrist and the tip
singularity_offset (float): minimal distance between the elbow position and the singularity position
singularity_limit_coeff (float): coefficient for the plane of the singularity limit
"""
if ik_parameters == {}:
print("Using default parameters")
ik_parameters = {
Expand Down Expand Up @@ -122,7 +144,15 @@ def is_reachable( # noqa C901
self, goal_pose: npt.NDArray[np.float64]
) -> Tuple[bool, npt.NDArray[np.float64], Optional[Any], str]:
# print(f" goal pose debut : {goal_pose}")
"""Check if the goal pose is reachable taking into account the limits of the wrist and the elbow"""
"""Check if the goal pose is reachable taking into account the limits of the wrist and the elbow
Args:
goal_pose : a 2D array with position [x,y,z] and Euler orientation [roll,pitch,yaw] (deg)
Returns:
bool: True if the goal pose is reachable
np.array: interval of the valid angles for the elbow
Optional[Callable]: function to get the joints from the angle of the elbow
str: if the goal is not reachable, the reason why
"""
state = ""
# Change goal pose if goal pose is out of reach or with x <= 0
is_reachable, goal_pose, reach_state = self.is_pose_in_robot_reach(goal_pose)
Expand Down
Loading