Skip to content

Commit

Permalink
Change jogging drift dimensions (moveit#63)
Browse files Browse the repository at this point in the history
* Add service file to control moveit_jog_arm free dimensions

* A better-sounding description

* Change service name to ChangeDriftDimensions

* Reword control_x_translation -> drift_x_translation

* Add a transform to the service

* Update srv/ChangeDriftDimensions.srv comment

Co-Authored-By: Dave Coleman <dave@picknik.ai>

Co-authored-by: Dave Coleman <dave@picknik.ai>
  • Loading branch information
2 people authored and tylerjw committed May 4, 2020
1 parent 4a45a3f commit 984e689
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ CheckIfRobotStateExistsInWarehouse.srv
RenameRobotStateInWarehouse.srv
DeleteRobotStateFromWarehouse.srv
ChangeControlDimensions.srv
ChangeDriftDimensions.srv
)

set(ACT_FILES
Expand Down
17 changes: 17 additions & 0 deletions srv/ChangeDriftDimensions.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
# For use with moveit_jog_arm Cartesian planner
#
# Allow the robot to drift along these dimensions in a smooth but unregulated way.
# Give 'true' to enable drift in the direction, 'false' to disable.
# For example, may allow wrist rotation by drift_x_rotation == true.
bool drift_x_translation
bool drift_y_translation
bool drift_z_translation
bool drift_x_rotation
bool drift_y_rotation
bool drift_z_rotation

# Not implemented as of Jan 2020 (for now assumed to be the identity matrix). In the future it will allow us to transform
# from the jog control frame to a unique drift frame, so the robot can drift along off-principal axes
geometry_msgs/Transform transform_jog_frame_to_drift_frame
---
bool success

0 comments on commit 984e689

Please sign in to comment.