-
Notifications
You must be signed in to change notification settings - Fork 29
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Added SetForceMode srv #20
base: melodic-devel
Are you sure you want to change the base?
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -25,6 +25,7 @@ add_service_files( | |
SetPayload.srv | ||
SetSpeedSliderFraction.srv | ||
SetIO.srv | ||
SetForceMode.srv | ||
) | ||
|
||
|
||
|
Original file line number | Diff line number | Diff line change | ||||
---|---|---|---|---|---|---|
@@ -0,0 +1,21 @@ | ||||||
# A 6d pose vector that defines the force frame relative to the base 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 | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. This is not a 6d vector anymore, a final docstring can be done once we figured out the task frame above. |
||||||
bool selection_vector_x | ||||||
bool selection_vector_y | ||||||
bool selection_vector_z | ||||||
bool selection_vector_rx | ||||||
bool selection_vector_ry | ||||||
bool selection_vector_rz | ||||||
Comment on lines
+5
to
+10
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I'm not sure whether "selection_vector" is the best naming. Maybe something like "compliance_x" would be more suitable? |
||||||
|
||||||
# A 6d vector. The forces/torques the robot will apply to its environment | ||||||
geometry_msgs/WrenchStamped wrench | ||||||
|
||||||
# An integer [1;3] specifying how the robot interprets the force frame | ||||||
uint8 type | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. The types should probably be explained / use constants. |
||||||
|
||||||
# 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 | ||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more.
Suggested change
|
||||||
geometry_msgs/TwistStamped limits | ||||||
--- | ||||||
bool success |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm not sure whether this makes sense. From what I understand, the target wrench is given in the task_frame, right? So, when using a
WrenchStamped
for the target wrench, the pose would be given through theframe_id
.