From 8e348726f67e3c80cf65b966c4caa73ec9e34858 Mon Sep 17 00:00:00 2001 From: Alex Mitrevski Date: Sun, 1 Nov 2020 15:59:24 +0100 Subject: [PATCH] [place_action/clients] Setting 'release_on_impact' in the place and throw clients The field is set to true and false respectively (we want to detect surface impact while placing, but we don't want to wait for impact while throwing an object) --- .../mdr_place_action/ros/scripts/place_client | 4 ++++ .../mdr_place_action/ros/scripts/throw_client | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/place_client b/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/place_client index d62bfd2ed..bc317ad72 100755 --- a/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/place_client +++ b/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/place_client @@ -75,6 +75,10 @@ class PlaceClient(ActionClientBase): self.robot_name = param.value goal.pose = self.get_placing_pose() + + # we want to place the object by detecting impact with the placing surface + goal.release_on_impact = True + return goal def get_placing_pose(self): diff --git a/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/throw_client b/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/throw_client index 21ea56e9c..58d5d6ccf 100755 --- a/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/throw_client +++ b/mdr_planning/mdr_actions/mdr_manipulation_actions/mdr_place_action/ros/scripts/throw_client @@ -72,6 +72,10 @@ class ThrowClient(ActionClientBase): self.robot_name = param.value goal.pose = self.get_throwing_pose() + + # we don't want to wait for impact when throwing the object + goal.release_on_impact = False + return goal def get_throwing_pose(self):