Package edu.tufts.hrilab.fetch
Class FetchComponent
java.lang.Object
edu.tufts.hrilab.diarc.DiarcComponent
edu.tufts.hrilab.moveit.MoveItComponent
edu.tufts.hrilab.fetch.FetchComponent
- All Implemented Interfaces:
FetchInterface
,ArmInterface
,LearningInterface
,MoveItInterface
- Direct Known Subclasses:
FetchItComponent
-
Field Summary
Fields inherited from class edu.tufts.hrilab.moveit.MoveItComponent
configName, defaultConfigDir, eePoses, eeTransform, endEffectorNames, grippers, initStartPose, jointNames, jointStateSub, moveGroup, moveItConfig, poses, recordedTrajectories, recordingTrajectory, trajectoriesFile
Fields inherited from class edu.tufts.hrilab.diarc.DiarcComponent
executionLoopCycleTime, log, shouldRunExecutionLoop
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionprotected List<org.apache.commons.cli.Option>
Command line options available in sub-class.checkGrasping
(Term graspingTerm) getBreakerState
(String breakerName) Gets the specified breaker state.float
Gets the charge level of the fetchprotected void
init()
Perform any component initialization.moveObject
(Symbol objectRef, String arm, String direction) Move arms(s) to location of chosen grasp specified in MemoryObject.protected void
parseArgs
(org.apache.commons.cli.CommandLine cmdLine) Called directly after construction to pass runtime values that will override default values.boolean
pointHeadTo
(Symbol objectRef) Point head in direction of target object in base_link coordinate frame.boolean
pointHeadTo
(MemoryObject target_object) Point head in direction of target object in base_link coordinate frame.boolean
pointHeadTo
(javax.vecmath.Point3d targetPosition) Point head in direction of target point in base_link coordinate frame.setBreakerState
(String breakerName, boolean state) Sends a breaker command request to set the given breaker to the desired state.boolean
setTorsoPosition
(double position) Move the torso to desired joint position.Methods inherited from class edu.tufts.hrilab.moveit.MoveItComponent
addCollisionObject, addLocalStaticTransforms, attachCollisionObject, attachCollisionObject, closeGripper, connectToMoveGroup, detachAllAttachedCollisionObjects, detachCollisionObject, detachCollisionObject, disableCarryingConstraints, disableCollisionAvoidance, enableCarryingConstraints, enableCollisionAvoidance, executeMotionPlanRequest, executeTrajectory, getEEPose, getGripperPosition, getPose, getPoses, getPoses, getRobotState, goToEEPose, goToPose, goToPose, goToStartPose, goToStartPose, graspObject, interrupt, isMoveGroupConnected, learn, loadEEPosesFromFile, loadPosesFromFile, loadTrajectoriesFromFile, moveGripper, moveGrippers, moveTo, moveTo, moveTo, moveTo, moveTo, moveToApproach, moveToCartesian, moveToJointPosition, moveToJointPositions, moveToJointPositions, moveToRelative, notOneArm, openGripper, pointTo, pointTo, pour, pressObject, pressObject, publishPointCloudToRos, pushObject, reconnectToMoveGroup, recordEEPose, recordPose, releaseObject, removeAllCollisionObjects, removeCollisionObject, saveEEPosesToFile, savePosesToFile, saveTrajectoriesToFile, setObjectCollisions, startRecordingTrajectory, stopRecordingTrajectory, unlearn
Methods inherited from class edu.tufts.hrilab.diarc.DiarcComponent
createInstance, createInstance, createInstance, createInstance, executionLoop, getMyGroupConstraints, getMyGroups, getMyService, getMyServices, main, shutdown, shutdownComponent
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
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, moveToRelative, openGripper, pointTo, pressObject, pressObject, recordPose, releaseObject, saveEEPosesToFile, savePosesToFile, saveTrajectoriesToFile, startRecordingTrajectory, stopRecordingTrajectory
Methods inherited from interface edu.tufts.hrilab.interfaces.LearningInterface
learn, unlearn
Methods inherited from interface edu.tufts.hrilab.moveit.MoveItInterface
disableCarryingConstraints, enableCarryingConstraints, goToStartPose, moveToCartesian, moveToJointPosition, moveToJointPositions, moveToJointPositions, pointTo, publishPointCloudToRos
-
Constructor Details
-
FetchComponent
public FetchComponent()
-
-
Method Details
-
init
protected void init()Description copied from class:DiarcComponent
Perform any component initialization. This should not be used for setting local fields to default values as was the case in DIARC. This method is called after the constructor, and after parseArgs. Setting default values should be done in field declaration or in the constructor.- Overrides:
init
in classMoveItComponent
-
additionalUsageInfo
Description copied from class:DiarcComponent
Command line options available in sub-class. This should be paired with a parseArgs implementation.- Overrides:
additionalUsageInfo
in classMoveItComponent
- Returns:
-
parseArgs
protected void parseArgs(org.apache.commons.cli.CommandLine cmdLine) Description copied from class:DiarcComponent
Called directly after construction to pass runtime values that will override default values. This should parse all the options that additionalUsageInfo provides.zs- Overrides:
parseArgs
in classMoveItComponent
-
pointHeadTo
Description copied from interface:FetchInterface
Point head in direction of target object in base_link coordinate frame.- Specified by:
pointHeadTo
in interfaceFetchInterface
- Returns:
-
pointHeadTo
Description copied from interface:FetchInterface
Point head in direction of target object in base_link coordinate frame. Alternative method to pointHeadTo that takes in POWER ref instead of MemoryObject.- Specified by:
pointHeadTo
in interfaceFetchInterface
- Returns:
-
pointHeadTo
public boolean pointHeadTo(javax.vecmath.Point3d targetPosition) Description copied from interface:FetchInterface
Point head in direction of target point in base_link coordinate frame.- Specified by:
pointHeadTo
in interfaceFetchInterface
- Returns:
-
setTorsoPosition
public boolean setTorsoPosition(double position) Description copied from interface:FetchInterface
Move the torso to desired joint position.- Specified by:
setTorsoPosition
in interfaceFetchInterface
- Parameters:
position
- all the way down is 0.0, and all the way up is approximately 0.3- Returns:
- TODO: replace this with more general setJointPosition(String joint, double position) method
-
lookAround
- Specified by:
lookAround
in interfaceFetchInterface
-
moveTo
Description copied from interface:ArmInterface
Move 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.- Specified by:
moveTo
in interfaceArmInterface
- Overrides:
moveTo
in classMoveItComponent
- Returns:
- true on success, false on failure. This function blocks.
-
checkGrasping
- Specified by:
checkGrasping
in interfaceFetchInterface
-
moveObject
- Specified by:
moveObject
in interfaceFetchInterface
-
look
- Specified by:
look
in interfaceFetchInterface
-
getChargeLevel
public float getChargeLevel()Description copied from interface:FetchInterface
Gets the charge level of the fetch- Specified by:
getChargeLevel
in interfaceFetchInterface
- Returns:
- The charge level of the fest (between 0-1) or -1 if battery state is null (likely not being published)
-
getBreakerState
Description copied from interface:FetchInterface
Gets the specified breaker state.- Specified by:
getBreakerState
in interfaceFetchInterface
- Parameters:
breakerName
- The name of the breaker. Currently, these are the relevant breakers: computer_breaker, battery_breaker, supply_breaker, base_breaker, arm_breaker, gripper_breaker.- Returns:
- An enumerated FetchBreakerStates object representing the states of the breaker or null if robot state is null/not being published or the breaker name cannot be found)
-
setBreakerState
Description copied from interface:FetchInterface
Sends a breaker command request to set the given breaker to the desired state.- Specified by:
setBreakerState
in interfaceFetchInterface
- Parameters:
breakerName
- The name of the breaker. Current settable breakers: base_breaker, arm_breaker, gripper_breakerstate
- The desired state of the specified breaker. TRUE means ON and FALSE means OFF.- Returns:
- An enumerated FetchBreakerStates object representing the actual resultant state of the breaker (i.e. if the E-stop is on, and you try to turn on the breaker it will still be off). A null return value likely means the breaker name is not valid/cannot be found.
-