Interface FetchInterface

All Superinterfaces:
ArmInterface, LearningInterface, MoveItInterface
All Known Subinterfaces:
FetchItInterface
All Known Implementing Classes:
FetchComponent, FetchItComponent, MockFetchComponent, MockFetchItComponent

public interface FetchInterface extends MoveItInterface
  • Method Details

    • setTorsoPosition

      boolean setTorsoPosition(double position)
      Move the torso to desired joint position.
      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
    • pointHeadTo

      boolean pointHeadTo(MemoryObject target_object)
      Point head in direction of target object in base_link coordinate frame.
      Parameters:
      target_object -
      Returns:
    • pointHeadTo

      boolean pointHeadTo(Symbol objectRef)
      Point head in direction of target object in base_link coordinate frame. Alternative method to pointHeadTo that takes in POWER ref instead of MemoryObject.
      Parameters:
      objectRef -
      Returns:
    • pointHeadTo

      boolean pointHeadTo(javax.vecmath.Point3d target_point)
      Point head in direction of target point in base_link coordinate frame.
      Parameters:
      target_point -
      Returns:
    • checkGrasping

      List<Map<Variable,Symbol>> checkGrasping(Term graspingTerm)
    • moveObject

      Justification moveObject(Symbol objectRef, String arm, String direction)
    • look

      Justification look(String direction)
    • lookAround

      Justification lookAround()
    • getChargeLevel

      float getChargeLevel()
      Gets the charge level of the fetch
      Returns:
      The charge level of the fest (between 0-1) or -1 if battery state is null (likely not being published)
    • getBreakerState

      FetchBreakerStates getBreakerState(String breakerName)
      Gets the specified breaker state.
      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

      FetchBreakerStates setBreakerState(String breakerName, boolean state)
      Sends a breaker command request to set the given breaker to the desired state.
      Parameters:
      breakerName - The name of the breaker. Current settable breakers: base_breaker, arm_breaker, gripper_breaker
      state - 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.