Skip to content
Draft
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
15 changes: 12 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()

find_package(ament_cmake REQUIRED)
find_package(ament_cmake_python REQUIRED)
find_package(Python3 REQUIRED COMPONENTS Interpreter)
find_package(rclpy REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)
Expand All @@ -14,17 +16,24 @@ find_package(geometry_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"srv/PlanCartesianPath.srv"
"srv/PlanScanPath.srv"
"action/PlanSpline.action"
DEPENDENCIES geometry_msgs
)


install(
PROGRAMS cartesian_planner/slerp_planner.py
PROGRAMS cartesian_planner/spline_planner.py
DESTINATION lib/${PROJECT_NAME}
RENAME slerp_planner
RENAME spline_planner
)


install(
DIRECTORY cartesian_planner/
DESTINATION lib/python${Python3_VERSION_MAJOR}.${Python3_VERSION_MINOR}/site-packages/cartesian_planner
FILES_MATCHING PATTERN "*.py"
)


ament_export_dependencies(rosidl_default_runtime)
Expand Down
72 changes: 28 additions & 44 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,61 +1,45 @@
# Cartesian Planner
# Cartesian Planner (Spline)

This package provides a standalone ROS 2 service that converts absolute end-effector
targets into a sequence of waypoints using spherical linear interpolation (SLERP).
This package provides a ROS 2 action server that converts an end-effector–frame goal pose into a spline of waypoints and executes them through `ArmControl`.

## Node Overview
## Nodes

`slerp_planner` is a Python node (`cartesian_planner/slerp_planner.py`) that exposes a
single ROS 2 service:
- `spline_planner` (`cartesian_planner/spline_planner.py`): Action server `spline_plan` (action: `cartesian_planner/PlanSpline`). Goal pose is expressed in the EE frame; the node looks up the current EE pose, transforms the goal to the base frame, builds a cubic spline for translation, keeps orientation fixed, converts to relative deltas, and feeds them sequentially to `ArmControl`.

```
/plan_cartesian_path (cartesian_planner/srv/PlanCartesianPath)
```

The request contains:

- `target_pose` – absolute goal pose, expressed in any TF frame (default
`eddie_base_link`).
- `max_translation_step` – maximum linear distance for each waypoint.
- `max_rotation_step` – maximum angular change per waypoint (radians).

The response returns:

- `relative_waypoints` – a list of incremental poses that can be sent directly to the
Eddie arm `ArmControl` action (which expects relative offsets).
- `success`/`message` – status of the planning call.


## Usage
- Run [Eddie-Ros](https://github.com/Robots4Sustainability/eddie-ros/tree/dev)

### Standalone

```
ros2 run cartesian_planner slerp_planner
```
- Run the planner:
```
ros2 run cartesian_planner spline_planner
```

**!! Please try only in simulation !!** :
- CLI test (send a +5 cm EE-frame move in Z):
```
ros2 action send_goal spline_plan cartesian_planner/action/PlanSpline "{ target_pose: { position: {x: 0.0, y: 0.0, z: 0.05}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0} } }"
```

```
ros2 launch eddie_ros eddie.launch.py use_sim:=true arm_select:=right
```
```
ros2 launch eddie_ros rviz.launch.py
```

**please ensure branch : `dsl/pick_place_fsm` for Finite-State-Machine**
The action result returns `success`/`message`; feedback publishes progress (0–1). Relative waypoints are sent directly to `right_arm/arm_control`.

```
ros2 run pick_place_fsm pick_place_fsm_mock
```
publish Pose
## Raster Scan

```
ros2 topic pub --once /perception/target_pose geometry_msgs/msg/PoseStamped "{header: {frame_id: eddie_base_link }, pose: {position: {x: 0, y: 0.5, z: 0}, orientation: {x: 0.0, y: 0.0, z: 0.0, w: 1.0}}}"
The `spline_planner` also exposes a service to perform a raster scan motion relative to a center pose.

```
- **Service**: `/plan_scan_path` (`cartesian_planner/srv/PlanScanPath`)
- **Example**:
```bash
ros2 service call /plan_scan_path cartesian_planner/srv/PlanScanPath "{center_pose: {header: {frame_id: eddie_base_link}, pose: {position: {x: 0.5, y: -0.3, z: 0.7}, orientation: {w: 1.0}}}, width: 0.5, height: 0.2, spacing: 0.05, line_spacing: 0.1}"
```

The service returns the incremental waypoints; a client can feed these to the
`right_arm/arm_control` action in sequence.
### Parameters

- **center_pose**: The center point `(x, y, z)` of the scan pattern.
- The scan is generated in the **Y-Z plane** of the base frame at the specified `x` depth.
- **width**: Total extent of the scan area along the **Y-axis** (horizontal).
- **height**: Total extent of the scan area along the **Z-axis** (vertical).
- **spacing**: Distance between waypoints along each horizontal line (scan resolution).
- **line_spacing**: Vertical distance between horizontal scan lines.

7 changes: 7 additions & 0 deletions action/PlanSpline.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# Goal: target pose expressed in end-effector frame (relative move)
geometry_msgs/Pose target_pose
---
bool success
string message
---
float32 progress
245 changes: 0 additions & 245 deletions cartesian_planner/slerp_planner.py

This file was deleted.

Loading