Skip to content
Merged
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
2 changes: 1 addition & 1 deletion tutorial_3/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -229,6 +229,6 @@ v.loadPath(p1)
v.loadPath(p2)
v.loadPath(p3)
```
The drilling path is a little bit naive since the tool trajectory is a straight line but the result of an interpolation in joint space and the velocities of the robot and tool are not controlled.
The drilling path is a little bit naive since the tool trajectory is not a straight line but the result of an interpolation in joint space and the velocities of the robot and tool are not controlled.

[Tutorial 4](../tutorial_4/README.md) shows how to better control a tool trajectory.
4 changes: 2 additions & 2 deletions tutorial_5/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ p2 = bezier.optimize(p1)
print(f"Smoothed path length: {p2.length():.3f} (was {p1.length():.3f})")
```

The resulting path is C²-continuous — a prerequisite for producing a smooth velocity profile in
The resulting path is continuously differentiable (C1), a prerequisite for producing a smooth velocity profile in
the next step.

## Time parameterization
Expand Down Expand Up @@ -91,7 +91,7 @@ Parameters:
Compare the profiles with and without Bézier smoothing:

```python
fig = plotTraj(toppra.optimize(p1), 0, 7, order=2)
fig = plotTraj(p3, 0, 7, order=2)
fig.show()
fig = plotTraj(p3, 0, 7, order=2)
fig.show()
Expand Down
6 changes: 5 additions & 1 deletion tutorial_6/Dockerfile
Original file line number Diff line number Diff line change
Expand Up @@ -12,9 +12,13 @@ ARG FRANKA_ROS2_VERSION=v3.2.2
USER root

# ROS2 control packages
RUN apt-get update -y && DEBIAN_FRONTEND=noninteractive apt-get install -qqy \
RUN apt-get update -y \
&& DEBIAN_FRONTEND=noninteractive apt-get dist-upgrade -qqy \
&& DEBIAN_FRONTEND=noninteractive apt-get install -qqy \
ros-jazzy-fastcdr \
ros-jazzy-control-msgs \
ros-jazzy-trajectory-msgs \
ros-jazzy-joint-state-broadcaster \
ros-jazzy-joint-trajectory-controller \
ros-jazzy-controller-manager \
ros-jazzy-ros2controlcli \
Expand Down
79 changes: 49 additions & 30 deletions tutorial_7/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@ adds the gripper: the robot must open the fingers before approaching the box,
close them before transport, then open them again at the goal.

The script plans a pick-and-place path with an HPP manipulation constraint
graph. We then use `hpp_exec` to split the path at grasp and release
transitions and execute each segment on Gazebo.
graph. We then use `hpp_exec` to expose the graph segments, attach the Gazebo
actions for this problem, and execute the segments.

For the full `hpp_exec` API, see the
[hpp-exec documentation](https://gepetto.github.io/doc/hpp-exec/doxygen-html/index.html).
Expand Down Expand Up @@ -52,7 +52,9 @@ python -i init.py

The script loads the FR3, the ground, and a box. It solves a pick-and-place
problem that moves the box from `(0.4, -0.2)` to `(0.4, 0.2)`, optimizes the
path, and time-parameterizes it with `SimpleTimeParameterization`.
path, time-parameterizes it with `SimpleTimeParameterization`.

Note that between optimization and time parameterization, an object called `EnforceTransitionSemantic` is called. This steps labels each sub-path with the transition of the graph the sub-path belongs to. This step is necessary before executing the path in order to place pre-actions and post-actions at the right times.

You can visualize the planned path in the browser viewer:

Expand All @@ -66,52 +68,61 @@ At this point the useful objects are:
- `p_timed`: the time-parameterized HPP path.
- `configs`: sampled HPP configurations along the timed path.
- `times`: timestamps in seconds, returned by `segments_from_graph`.
- `segments`: executable arm trajectory slices with gripper pre-actions.
- `segments`: graph segments where you can add pre/post actions.
- `graph`: the HPP manipulation constraint graph.
- `open_gripper`, `close_gripper`, `grasp_box`, and `release_box`: small
Gazebo actions for the gripper and simulated box attachment.
- `open_gripper`, `close_gripper`, `grasp_box`, and `release_box`: Gazebo
actions for the gripper and simulated box attachment.

## Building execution segments

The planned path contains the approach, transport, and retreat motion in one
path. To execute it, ask `hpp_exec` to sample the timed path, insert graph
transition boundaries, and split the arm motion where a gripper action is
needed:
path. Ask `hpp_exec` to sample the timed path and expose the HPP graph
segments:

```python
from hpp_exec import segments_from_graph
from hpp_exec import print_segments, segments_from_graph

configs, times, segments = segments_from_graph(
p_timed, graph,
on_grasp=grasp_box,
on_release=release_box,
)
configs, times, segments = segments_from_graph(p_timed, graph)
print_segments(segments)
```

For this problem, `segments` contains three phases:

| # | Phase | What the arm does | Pre-action |
|---|-----------|-----------------------------|------------|
| 0 | approach | move above the box, descend | none |
| 1 | transport | carry the box to the goal | attach and close |
| 2 | retreat | lift and return | open and detach |
The table shows the segment times, graph transition names, nominal states,
observed states, and how many pre/post actions are attached.

Make the initial gripper state explicit before the approach:
For this tutorial, use the rows named
`fr3/gripper > box/handle | f_23` and
`fr3/gripper < box/handle | 0-0_32`. With the current path they are segments
2 and 4:

```python
segments[0].pre_actions.insert(0, open_gripper)
segments[0].pre_actions.append(open_gripper)

# 2: fr3/gripper > box/handle | f_23
segments[2].pre_actions.append(grasp_box)

# 4: fr3/gripper < box/handle | 0-0_32
segments[4].pre_actions.append(release_box)

print_segments(segments)
```

This matters if a previous run left the simulated gripper closed.
Conceptually, execution has three phases:

| # | Phase | What the arm does | Action before phase |
|---|-----------|-----------------------------|---------------------|
| 0 | approach | move above the box, descend | open |
| 1 | transport | carry the box to the goal | attach and close |
| 2 | retreat | lift and return | open and detach |

## Executing the segments

Send the arm segments to the arm controller and let the pre-actions command
Send the arm segments to the arm controller and let the segment actions command
the gripper controller:

```python
from hpp_exec import execute_segments

reset_box_pose()
execute_segments(
segments, configs, times,
joint_names=[f"fr3_joint{i}" for i in range(1, 8)],
Expand All @@ -122,8 +133,16 @@ execute_segments(
You should see the fingers open, the arm descend, the fingers close on the
box, the arm carry the box to the goal, the fingers open, and the arm retreat.

`init.py` also defines this convenience wrapper:
`reset_box_pose()` detaches the simulated box if needed and places it back at
the planned start pose before execution.

```python
execute_on_gazebo()
```
## More details about the pre and post actions

In script `init.py` several functions are defined.

- `open_gripper` and `close_gripper` sends a reference value for "fr3_finger_joint1" in order
to open or close the gripper. This function uses `send_trajectory` to do so, as in
`tutorial_6`. On the real robot, this is performed by a ROS action instead.
- `grasp_box` and `release_box` call `attach_box` and `detach_box` respectively. These functions
tell gazebo that the box is attached to or detached from the end effector. They are useless on
the real robot.
Loading