From 92a38d1232e345317cf3a38ce2ef24f3ab8e1ebf Mon Sep 17 00:00:00 2001 From: urmarp Date: Mon, 9 Jan 2023 09:48:17 +0100 Subject: [PATCH 1/2] Added SetForceMode srv --- CMakeLists.txt | 1 + srv/SetForceMode.srv | 16 ++++++++++++++++ 2 files changed, 17 insertions(+) create mode 100644 srv/SetForceMode.srv diff --git a/CMakeLists.txt b/CMakeLists.txt index 3320017..e9af77d 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -25,6 +25,7 @@ add_service_files( SetPayload.srv SetSpeedSliderFraction.srv SetIO.srv + SetForceMode.srv ) diff --git a/srv/SetForceMode.srv b/srv/SetForceMode.srv new file mode 100644 index 0000000..72cbbb7 --- /dev/null +++ b/srv/SetForceMode.srv @@ -0,0 +1,16 @@ +# A 6d pose vector that defines the force frame relative to the base frame +float64[] task_frame + +# A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding axis of the task frame +float64[] selection_vector + +# A 6d vector. The forces/torques the robot will apply to its environment +float64[] wrench + +# An integer [1;3] specifying how the robot interprets the force frame +uint8 type + +# 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual tcp position and the one set by the program +float32[] limits +--- +bool success \ No newline at end of file From b98a7111303dc77146e5f84914de30989cdd958a Mon Sep 17 00:00:00 2001 From: urmarp Date: Mon, 30 Jan 2023 17:19:12 +0100 Subject: [PATCH 2/2] Changed msg types to be more representative --- srv/SetForceMode.srv | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/srv/SetForceMode.srv b/srv/SetForceMode.srv index 72cbbb7..581c5c3 100644 --- a/srv/SetForceMode.srv +++ b/srv/SetForceMode.srv @@ -1,16 +1,21 @@ # A 6d pose vector that defines the force frame relative to the base frame -float64[] task_frame +geometry_msgs/PoseStamped task_frame # A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding axis of the task frame -float64[] selection_vector +bool selection_vector_x +bool selection_vector_y +bool selection_vector_z +bool selection_vector_rx +bool selection_vector_ry +bool selection_vector_rz # A 6d vector. The forces/torques the robot will apply to its environment -float64[] wrench +geometry_msgs/WrenchStamped wrench # An integer [1;3] specifying how the robot interprets the force frame uint8 type # 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual tcp position and the one set by the program -float32[] limits +geometry_msgs/TwistStamped limits --- bool success \ No newline at end of file