Skip to content

Commit 16bb3f6

Browse files
authored
Improve Bite Transfer (#72)
* Reverted to in-front staging location, added a cartesian motion to mouth * MoveToMouth and MoveFromMouth works well in sim * Add cleanup to turn watchdog listener on to MoveToRestingPosition and MoveAbovePlate * Added ability to specific separate orientaiton constraints for staging location vs end config for MoveFromMouth * Added velocity scaling to MoveFromMouth * Made cartesian motions avoid collision * Updated README.md * Move the staging location down, adjust the planning scene based on the real table location * Added ability to set pipeline id * Added ability to set acceleration scaling * Add velocity scaling to cartesian planning * Formatting and linting * Added more granular control for cartesian planning * Fix cartesian velocity scaling * Linting * Fix the MoveFromMouth staging location to be the new lower staging location * Added a min distance to use a detected face * Final polishing * Fix face detection out-of-bounds bug * Remove unnecessary ReentrantCallbackGroup * Make toggle collision object asynch * Linting
1 parent a7180a9 commit 16bb3f6

16 files changed

+1072
-165
lines changed

ada_feeding/README.md

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ This code has been developed and tested with the Kinova JACO Gen2 Arm, on comput
88
- Install [ROS2 Humble](https://docs.ros.org/en/humble/Installation.html)
99
- Install Python dependencies: `python3 -m pip install pyyaml py_trees pymongo tornado trimesh`
1010
- Install the code to command the real robot ([instructions here](https://github.com/personalrobotics/ada_ros2/blob/main/README.md))
11-
- Git clone the [PRL fork of pymoveit (branch: `amaln/allowed_collision_matrix`)](https://github.com/personalrobotics/pymoveit2) and the [PRL fork of py_trees_ros (branch: `amaln/service_client`)](https://github.com/personalrobotics/py_trees_ros/tree/amaln/service_client) into your ROS2 workspace's `src` folder.
11+
- Git clone the [PRL fork of pymoveit (branch: `amaln/cartesian_allow_collision`)](https://github.com/personalrobotics/pymoveit2/tree/amaln/cartesian_avoid_collision) and the [PRL fork of py_trees_ros (branch: `amaln/service_client`)](https://github.com/personalrobotics/py_trees_ros/tree/amaln/service_client) into your ROS2 workspace's `src` folder.
1212
- Install additional dependencies: `sudo apt install ros-humble-py-trees-ros-interfaces`.
1313
- Install the web app into your workspace ([instructions here](https://github.com/personalrobotics/feeding_web_interface/tree/main/feedingwebapp)).
1414

@@ -21,7 +21,7 @@ This code has been developed and tested with the Kinova JACO Gen2 Arm, on comput
2121
4. Launch the RealSense & Perception:
2222
1. Dummy nodes: `ros2 launch feeding_web_app_ros2_test feeding_web_app_dummy_nodes_launch.xml run_motion:=false run_web_bridge:=false`
2323
2. Real nodes: Follow the instructions in the [`ada_feeding_perception` README](https://github.com/personalrobotics/ada_feeding/blob/ros2-devel/ada_feeding_perception/README.md#usage)
24-
5. Run the action servers: `ros2 launch ada_feeding ada_feeding_launch.xml`
24+
5. Ensure the e-stop is plugged in. Run the action servers: `ros2 launch ada_feeding ada_feeding_launch.xml`
2525
6. Launch MoveIt2:
2626
1. Sim (RVIZ): `ros2 launch ada_moveit demo_feeding.launch.py sim:=mock`
2727
2. Real Robot: `ros2 launch ada_moveit demo_feeding.launch.py`
@@ -31,7 +31,9 @@ This code has been developed and tested with the Kinova JACO Gen2 Arm, on comput
3131
2. `ros2 action send_goal /AcquireFood ada_feeding_msgs/action/AcquireFood "{header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''}, detected_food: {roi: {x_offset: 0, y_offset: 0, height: 0, width: 0, do_rectify: false}, mask: {header: {stamp: {sec: 0, nanosec: 0}, frame_id: ''}, format: '', data: []}, item_id: '', confidence: 0.0}}" --feedback`
3232
3. `ros2 action send_goal /MoveToRestingPosition ada_feeding_msgs/action/MoveTo "{}" --feedback`
3333
4. `ros2 action send_goal /MoveToMouth ada_feeding_msgs/action/MoveTo "{}" --feedback`
34-
5. `ros2 action send_goal /MoveToStowLocation ada_feeding_msgs/action/MoveTo "{}" --feedback`
34+
5. `ros2 action send_goal /MoveFromMouthToRestingPosition ada_feeding_msgs/action/MoveTo "{}" --feedback`
35+
6. `ros2 action send_goal /MoveFromMouthToAbovePlate ada_feeding_msgs/action/MoveTo "{}" --feedback`
36+
7. `ros2 action send_goal /MoveToStowLocation ada_feeding_msgs/action/MoveTo "{}" --feedback`
3537
2. Test the individual actions with the web app:
3638
1. Launch the web app ([instructions here](https://github.com/personalrobotics/feeding_web_interface/tree/main/feedingwebapp))
3739
2. Go through the web app, ensure the expected actions happen on the robot.

ada_feeding/ada_feeding/behaviors/move_to.py

Lines changed: 110 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -84,6 +84,10 @@ def __init__(
8484
self.move_to_blackboard.register_key(
8585
key="cartesian", access=py_trees.common.Access.READ
8686
)
87+
# Add the ability to set a pipeline_id
88+
self.move_to_blackboard.register_key(
89+
key="pipeline_id", access=py_trees.common.Access.READ
90+
)
8791
# Add the ability to set a planner_id
8892
self.move_to_blackboard.register_key(
8993
key="planner_id", access=py_trees.common.Access.READ
@@ -96,6 +100,24 @@ def __init__(
96100
self.move_to_blackboard.register_key(
97101
key="max_velocity_scaling_factor", access=py_trees.common.Access.READ
98102
)
103+
# Add the ability to set acceleration scaling
104+
self.move_to_blackboard.register_key(
105+
key="max_acceleration_scaling_factor", access=py_trees.common.Access.READ
106+
)
107+
# Add the ability to set the cartesian jump threshold
108+
self.move_to_blackboard.register_key(
109+
key="cartesian_jump_threshold", access=py_trees.common.Access.READ
110+
)
111+
# Add the ability to set the cartesian max step
112+
self.move_to_blackboard.register_key(
113+
key="cartesian_max_step", access=py_trees.common.Access.READ
114+
)
115+
# Add the ability to set a cartesian fraction threshold (e.g., only
116+
# accept plans that completed at least this fraction of the path)
117+
self.move_to_blackboard.register_key(
118+
key="cartesian_fraction_threshold", access=py_trees.common.Access.READ
119+
)
120+
99121
# Initialize the blackboard to read from the parent behavior tree
100122
self.tree_blackboard = self.attach_blackboard_client(
101123
name=name + " MoveTo", namespace=tree_name
@@ -144,6 +166,15 @@ def initialise(self) -> None:
144166
self.logger.info(f"{self.name} [MoveTo::initialise()]")
145167

146168
with self.moveit2_lock:
169+
# Set the planner_id
170+
self.moveit2.planner_id = get_from_blackboard_with_default(
171+
self.move_to_blackboard, "planner_id", "RRTstarkConfigDefault"
172+
)
173+
# Set the pipeline_id
174+
self.moveit2.pipeline_id = get_from_blackboard_with_default(
175+
self.move_to_blackboard, "pipeline_id", "ompl"
176+
)
177+
147178
# Set the planner_id
148179
self.moveit2.planner_id = get_from_blackboard_with_default(
149180
self.move_to_blackboard, "planner_id", "RRTstarkConfigDefault"
@@ -159,6 +190,39 @@ def initialise(self) -> None:
159190
self.move_to_blackboard, "allowed_planning_time", 0.5
160191
)
161192

193+
# Set the max acceleration
194+
self.moveit2.max_acceleration = get_from_blackboard_with_default(
195+
self.move_to_blackboard, "max_acceleration_scaling_factor", 0.1
196+
)
197+
198+
# Set the allowed planning time
199+
self.moveit2.allowed_planning_time = get_from_blackboard_with_default(
200+
self.move_to_blackboard, "allowed_planning_time", 0.5
201+
)
202+
203+
# Set the cartesian jump threshold
204+
self.moveit2.cartesian_jump_threshold = get_from_blackboard_with_default(
205+
self.move_to_blackboard, "cartesian_jump_threshold", 0.0
206+
)
207+
208+
# Get whether we should use the cartesian interpolator
209+
self.cartesian = get_from_blackboard_with_default(
210+
self.move_to_blackboard, "cartesian", False
211+
)
212+
213+
# Get the cartesian max step
214+
self.cartesian_max_step = get_from_blackboard_with_default(
215+
self.move_to_blackboard, "cartesian_max_step", 0.0025
216+
)
217+
218+
# Get the cartesian fraction threshold
219+
self.cartesian_fraction_threshold = get_from_blackboard_with_default(
220+
self.move_to_blackboard, "cartesian_fraction_threshold", 0.0
221+
)
222+
223+
# If the plan is cartesian, it should always avoid collisions
224+
self.moveit2.cartesian_avoid_collisions = True
225+
162226
# Reset local state variables
163227
self.prev_query_state = None
164228
self.planning_start_time = time.time()
@@ -173,14 +237,8 @@ def initialise(self) -> None:
173237
self.tree_blackboard.motion_initial_distance = 0.0
174238
self.tree_blackboard.motion_curr_distance = 0.0
175239

176-
# Get all parameters for motion, resorting to default values if unset.
177-
self.joint_names = kinova.joint_names()
178-
self.cartesian = get_from_blackboard_with_default(
179-
self.move_to_blackboard, "cartesian", False
180-
)
181-
182240
# Set the joint names
183-
self.distance_to_goal.set_joint_names(self.joint_names)
241+
self.distance_to_goal.set_joint_names(kinova.joint_names())
184242

185243
# pylint: disable=too-many-branches, too-many-return-statements
186244
# This is the heart of the MoveTo behavior, so the number of branches
@@ -210,7 +268,9 @@ def update(self) -> py_trees.common.Status:
210268
return py_trees.common.Status.FAILURE
211269
# Initiate an asynchronous planning call
212270
with self.moveit2_lock:
213-
planning_future = self.moveit2.plan_async(cartesian=self.cartesian)
271+
planning_future = self.moveit2.plan_async(
272+
cartesian=self.cartesian, max_step=self.cartesian_max_step
273+
)
214274
if planning_future is None:
215275
self.logger.error(
216276
f"{self.name} [MoveTo::update()] Failed to initiate planning!"
@@ -228,7 +288,9 @@ def update(self) -> py_trees.common.Status:
228288
# Get the trajectory
229289
with self.moveit2_lock:
230290
traj = self.moveit2.get_trajectory(
231-
self.planning_future, cartesian=self.cartesian
291+
self.planning_future,
292+
cartesian=self.cartesian,
293+
cartesian_fraction_threshold=self.cartesian_fraction_threshold,
232294
)
233295
self.logger.info(f"Trajectory: {traj} | type {type(traj)}")
234296
if traj is None:
@@ -237,6 +299,11 @@ def update(self) -> py_trees.common.Status:
237299
)
238300
return py_trees.common.Status.FAILURE
239301

302+
# MoveIt's default cartesian interpolator doesn't respect velocity
303+
# scaling, so we need to manually add that.
304+
if self.cartesian and self.moveit2.max_velocity > 0.0:
305+
MoveTo.scale_velocity(traj, self.moveit2.max_velocity)
306+
240307
# Set the trajectory's initial distance to goal
241308
self.tree_blackboard.motion_initial_distance = (
242309
self.distance_to_goal.set_trajectory(traj)
@@ -350,6 +417,40 @@ def shutdown(self) -> None:
350417
"""
351418
self.logger.info(f"{self.name} [MoveTo::shutdown()]")
352419

420+
@staticmethod
421+
def scale_velocity(traj: JointTrajectory, scale_factor: float) -> None:
422+
"""
423+
Scale the velocity of the trajectory by the given factor. The resulting
424+
trajectory should execute the same trajectory with the same continuity,
425+
but just take 1/scale_factor as long to execute.
426+
427+
This function keeps positions the same and scales time, velocities, and
428+
accelerations. It does not modify effort.
429+
430+
Parameters
431+
----------
432+
traj: The trajectory to scale.
433+
scale_factor: The factor to scale the velocity by, in [0, 1].
434+
"""
435+
for point in traj.points:
436+
# Scale time_from_start
437+
nsec = point.time_from_start.sec * 10.0**9
438+
nsec += point.time_from_start.nanosec
439+
nsec /= scale_factor # scale time
440+
sec = int(math.floor(nsec / 10.0**9))
441+
point.time_from_start.sec = sec
442+
point.time_from_start.nanosec = int(nsec - sec * 10.0**9)
443+
444+
# Scale the velocities
445+
# pylint: disable=consider-using-enumerate
446+
# Necessary because we want to destructively modify the trajectory
447+
for i in range(len(point.velocities)):
448+
point.velocities[i] *= scale_factor
449+
450+
# Scale the accelerations
451+
for i in range(len(point.accelerations)):
452+
point.accelerations[i] *= scale_factor**2
453+
353454

354455
class DistanceToGoal:
355456
"""

ada_feeding/ada_feeding/behaviors/toggle_collision_object.py

Lines changed: 35 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,9 @@ class ToggleCollisionObject(py_trees.behaviour.Behaviour):
2323
scene.
2424
"""
2525

26+
# pylint: disable=too-many-instance-attributes
27+
# One over is fine.
28+
2629
def __init__(
2730
self,
2831
name: str,
@@ -60,6 +63,18 @@ def __init__(
6063
self.node,
6164
)
6265

66+
# pylint: disable=attribute-defined-outside-init
67+
# For attributes that are only used during the execution of the tree
68+
# and get reset before the next execution, it is reasonable to define
69+
# them in `initialise`.
70+
def initialise(self) -> None:
71+
"""
72+
Reset the service_future.
73+
"""
74+
self.logger.info(f"{self.name} [ToggleCollisionObject::initialise()]")
75+
76+
self.service_future = None
77+
6378
def update(self) -> py_trees.common.Status:
6479
"""
6580
(Dis)allow collisions between the robot and a collision
@@ -71,10 +86,24 @@ def update(self) -> py_trees.common.Status:
7186
"""
7287
self.logger.info(f"{self.name} [ToggleCollisionObject::update()]")
7388
# (Dis)allow collisions between the robot and the collision object
74-
with self.moveit2_lock:
75-
succ = self.moveit2.allow_collisions(self.collision_object_id, self.allow)
89+
if self.service_future is None:
90+
with self.moveit2_lock:
91+
service_future = self.moveit2.allow_collisions(
92+
self.collision_object_id, self.allow
93+
)
94+
if service_future is None: # service not available
95+
return py_trees.common.Status.FAILURE
96+
self.service_future = service_future
97+
return py_trees.common.Status.RUNNING
98+
99+
# Check if the service future is done
100+
if self.service_future.done():
101+
with self.moveit2_lock:
102+
succ = self.moveit2.process_allow_collision_future(self.service_future)
103+
# Return success/failure
104+
if succ:
105+
return py_trees.common.Status.SUCCESS
106+
return py_trees.common.Status.FAILURE
76107

77-
# Return success
78-
if succ:
79-
return py_trees.common.Status.SUCCESS
80-
return py_trees.common.Status.FAILURE
108+
# Return running
109+
return py_trees.common.Status.RUNNING

0 commit comments

Comments
 (0)