Package edu.tufts.hrilab.moveit
Interface MoveItInterface
- All Superinterfaces:
ArmInterface
,LearningInterface
- All Known Subinterfaces:
FetchInterface
,FetchItInterface
,PR2Interface
- All Known Implementing Classes:
FetchComponent
,FetchItComponent
,MockFetchComponent
,MockFetchItComponent
,MockMoveItComponent
,MockPR2Component
,MoveItComponent
,PR2Component
-
Method Summary
Modifier and TypeMethodDescriptionvoid
Turn off carrying orientation constraints.void
Turn on carrying orientation constraints.boolean
boolean
moveToCartesian
(String groupName, javax.vecmath.Point3d point, javax.vecmath.Quat4d orientation) boolean
moveToJointPosition
(String joint, double position) Deprecated.boolean
moveToJointPositions
(String[] jointNames, double[] positions) Deprecated.boolean
moveToJointPositions
(String[] joint_names, double[] positions, double[] velocities, double[] efforts) Deprecated.boolean
boolean
publishPointCloudToRos
(byte[] depthData) Publish the compressed depth data to ROS after being decompressed and converted to proper point cloud form.Methods inherited from interface edu.tufts.hrilab.interfaces.ArmInterface
closeGripper, executeTrajectory, getEEPose, getGripperPosition, getPose, goToPose, goToPose, goToStartPose, graspObject, loadEEPosesFromFile, loadPosesFromFile, loadTrajectoriesFromFile, moveGripper, moveTo, moveTo, moveTo, moveTo, moveToRelative, openGripper, pointTo, pressObject, pressObject, recordPose, releaseObject, saveEEPosesToFile, savePosesToFile, saveTrajectoriesToFile, startRecordingTrajectory, stopRecordingTrajectory
Methods inherited from interface edu.tufts.hrilab.interfaces.LearningInterface
learn, unlearn
-
Method Details
-
moveToJointPositions
@Deprecated boolean moveToJointPositions(String[] joint_names, double[] positions, double[] velocities, double[] efforts) Deprecated. -
moveToJointPositions
Deprecated. -
moveToJointPosition
Deprecated.Set the position of a single joint. All remaining joints will remain in the same position.- Parameters:
joint
- The name of the joint to manipulate, as found in `names` of /joint_statesposition
- The goal position, as viewed in /joint_states- Returns:
- true on success, false on failure. This function blocks.
-
enableCarryingConstraints
void enableCarryingConstraints()Turn on carrying orientation constraints. This will apply to all moveTo and goToPose methods. -
disableCarryingConstraints
void disableCarryingConstraints()Turn off carrying orientation constraints. -
pointTo
-
moveToCartesian
boolean moveToCartesian(String groupName, javax.vecmath.Point3d point, javax.vecmath.Quat4d orientation) -
goToStartPose
boolean goToStartPose() -
publishPointCloudToRos
boolean publishPointCloudToRos(byte[] depthData) Publish the compressed depth data to ROS after being decompressed and converted to proper point cloud form.- Parameters:
depthData
- A byte array containing the point cloud data.- Returns:
- true on success.
-