Package edu.tufts.hrilab.interfaces
Interface ArmInterface
- All Known Subinterfaces:
- FetchInterface,- FetchItInterface,- MockArmInterface,- MoveItInterface,- PR2Interface
- All Known Implementing Classes:
- FetchComponent,- FetchItComponent,- MockArmComponent,- MockFetchComponent,- MockFetchItComponent,- MockMoveItComponent,- MockPR2Component,- MockSpotComponent,- MockUR5eComponent,- MoveItComponent,- PR2Component
public interface ArmInterface
- 
Method SummaryModifier and TypeMethodDescriptioncloseGripper(String groupName) booleanexecuteTrajectory(String trajectoryName) Execute a previously recorded trajectory.org.apache.commons.lang3.tuple.Pair<javax.vecmath.Point3d,javax.vecmath.Quat4d> Convenience method of getPose that finds the end-effector link based on the passed in groupName.floatgetGripperPosition(String groupName) org.apache.commons.lang3.tuple.Pair<javax.vecmath.Point3d,javax.vecmath.Quat4d> Get the point and orientation of a link on the robot.booleanMove robot to previously recorded robot state/pose.booleanMove robot to previously recorded robot state/pose, using only the specified group name (e.g., right_arm).booleangoToStartPose(boolean safe) Go to the start pose saved in the JSON file.graspObject(String groupName, Symbol refId, float position) Close gripper(s) to specified amount and attach MemoryObject as a collision object.voidloadEEPosesFromFile(String filename) Load poses previously saved to file and make them accessible via goToPose.voidloadPosesFromFile(String filename) Load poses previously saved to file and make them accessible via goToPose.voidloadTrajectoriesFromFile(String filename) Load trajectories from a file that was generated via saveTrajectoriesToFile().booleanmoveGripper(String groupName, float meters) Move arms(s) to location of chosen grasp specified in MemoryObject.[ Move arms(s) to pose defined by the refId and constrained by a set of constraints.booleanMove the groupName to a pose.booleanmoveTo(String groupName, javax.vecmath.Point3d point_l, javax.vecmath.Quat4d orientation_l, javax.vecmath.Point3d point_r, javax.vecmath.Quat4d orientation_r) Move the groupName to specified poses(s).moveToRelative(String groupName, javax.vecmath.Point3d point, javax.vecmath.Quat4d orientation) Move a certain amount from the current location, without any squeezing or releasing.openGripper(String groupName) booleanPoint a groupName to an object.pressObject(String group_name, Symbol refID) Presses an object based off a given symbolpressObject(String group_name, javax.vecmath.Point3d object_location, javax.vecmath.Quat4d object_orientation) Presses an object based off a given posebooleanrecordPose(Symbol poseName) Record current robot state (i.e., joint positions), and name it.releaseObject(String groupName, Symbol refId, float position) Move arm(s) and open gripper(s) to specified amount and detach MemoryObject as collision object.booleansaveEEPosesToFile(String filename) Write the poses recorded via recordPose to file.booleansavePosesToFile(String filename) Write the poses recorded via recordPose to file.booleansaveTrajectoriesToFile(String filename) Take all trajectories saved via startRecordingTrajectory and save them to a file for later.voidstartRecordingTrajectory(String trajectoryName) Start recording a trajectory.voidStop recording the currently running trajectory recording.
- 
Method Details- 
moveToMove the groupName to a pose. Uses the default coordinate frame as set by JSON (defaulting to base_link).- Returns:
- true on success, false on failure. This function blocks.
 
- 
moveToboolean moveTo(String groupName, javax.vecmath.Point3d point_l, javax.vecmath.Quat4d orientation_l, javax.vecmath.Point3d point_r, javax.vecmath.Quat4d orientation_r) Move the groupName to specified poses(s). If group name only contains a single arm, use a different moveTo().Note that there's a baked-in assumption that the only two-arned nmachines will use a group name that is checked against in the 'isOneArm()' method (currently just "arms"). Update this function if this does not describe your use case. It also assumes that groupName "arms" can be described as independent movement of groupName "left_arm" and groupName "right_arm". At this point in time this is a safe assumption because of the state of the PR2's JSON config. point_l, orientation_l refer to the left arm, point_r and orientation_r refer to the right. - Returns:
- true on success, false on failure. This function blocks.
 
- 
moveToMove arms(s) to location of chosen grasp specified in MemoryObject. Uses the default "grasp_point(X)" constraint to select grasp points. Assumes default coordinate frame as set by JSON, defaulting to base_link. Note: gripper should already be open/closed before calling this method. This is an alternative method to moveTo that takes in POWER ref instead of MemoryObject.- Returns:
- true on success, false on failure. This function blocks.
 
- 
moveTo[ Move arms(s) to pose defined by the refId and constrained by a set of constraints. Assumes base_link coordinate frame. Note: gripper should already be open/closed before calling this method.- Parameters:
- constraints- a list of predicate constraints
- Returns:
- true on success, false on failure. This function blocks.
 
- 
moveToRelativeJustification moveToRelative(String groupName, javax.vecmath.Point3d point, javax.vecmath.Quat4d orientation) Move a certain amount from the current location, without any squeezing or releasing.- Parameters:
- groupName- the name of the arm or arms to move
- point- the amount of change in base frame the object is moved
- orientation- the amount to rotate the object in goal state from its current rotation in base frame
- Returns:
- success or failure to move. This function blocks.
 
- 
graspObjectClose gripper(s) to specified amount and attach MemoryObject as a collision object. Alternative method to graspObject that takes in POWER ref instead of MemoryObject.- Returns:
- true on success, false on failure. This function blocks.
 
- 
releaseObjectMove arm(s) and open gripper(s) to specified amount and detach MemoryObject as collision object. Alternative method to releaseObject that takes in POWER ref instead of MemoryObject.- Returns:
- true on success, false on failure. This function blocks.
 
- 
pointToPoint a groupName to an object.- Returns:
- true on success, false on failure. This function blocks
 
- 
getEEPoseorg.apache.commons.lang3.tuple.Pair<javax.vecmath.Point3d,javax.vecmath.Quat4d> getEEPose(String groupName) Convenience method of getPose that finds the end-effector link based on the passed in groupName.- Parameters:
- groupName-
- Returns:
 
- 
getPoseorg.apache.commons.lang3.tuple.Pair<javax.vecmath.Point3d,javax.vecmath.Quat4d> getPose(String linkName) Get the point and orientation of a link on the robot.
- 
recordPoseRecord current robot state (i.e., joint positions), and name it.- Parameters:
- poseName- The name of the pose to be saved.
- Returns:
- true on success, false on failure. This function blocks.
 
- 
saveEEPosesToFileWrite the poses recorded via recordPose to file.- Returns:
- true on success
 
- 
loadEEPosesFromFileLoad poses previously saved to file and make them accessible via goToPose.
- 
savePosesToFileWrite the poses recorded via recordPose to file.- Returns:
- true on success
 
- 
loadPosesFromFileLoad poses previously saved to file and make them accessible via goToPose.
- 
goToPoseMove robot to previously recorded robot state/pose, using only the specified group name (e.g., right_arm). Currently set to ignore gripper joints so it will leave grippers in current state of open/closed.- Parameters:
- groupName- which arm(s) should move (rightArm, leftArm, arms, etc)
- poseName- name of pose to move into
- Returns:
- true on success, false on failure. This function blocks.
 
- 
goToPoseMove robot to previously recorded robot state/pose. Currently set to ignore gripper joints so it will leave grippers in current state of open/closed.- Parameters:
- poseName- name of pose to move into
- Returns:
- true on success, false on failure. This function blocks.
 
- 
goToStartPoseboolean goToStartPose(boolean safe) Go to the start pose saved in the JSON file.- Returns:
- success
 
- 
startRecordingTrajectoryStart recording a trajectory. Trajectory recording can be started here, the robot can be physically manipulated, and then stopRecordingTrajectory can be called to stop the current recording.- Parameters:
- trajectoryName- The name of the trajectory to be saved.
 
- 
stopRecordingTrajectoryvoid stopRecordingTrajectory()Stop recording the currently running trajectory recording.
- 
executeTrajectoryExecute a previously recorded trajectory.- Returns:
- true on success, false on failure. This function blocks.
 
- 
saveTrajectoriesToFileTake all trajectories saved via startRecordingTrajectory and save them to a file for later.- Parameters:
- filename- Path to file
- Returns:
- true on success, false on failure.
 
- 
loadTrajectoriesFromFileLoad trajectories from a file that was generated via saveTrajectoriesToFile(). The loaded trajectories will then be executable via executeTrajectory().
- 
closeGripper
- 
openGripper
- 
moveGripper
- 
getGripperPosition
- 
pressObjectJustification pressObject(String group_name, javax.vecmath.Point3d object_location, javax.vecmath.Quat4d object_orientation) Presses an object based off a given pose- Parameters:
- group_name- The arm group to do the pressing (i.e. "arm")
- object_location- The location of the object relative to the base link
- object_orientation- The orientation of the object relative to the base link with the normal vector coming out of the object
- Returns:
- Condition Justification stating if the action is successful or not
 
- 
pressObjectPresses an object based off a given symbol- Parameters:
- group_name- The arm group to do the pressing (i.e. "arm")
- refID- Symbol representing the object to be pressed
- Returns:
- Condition Justification stating if the action is successful or not
 
 
-