Class FetchComponent

All Implemented Interfaces:
FetchInterface, ArmInterface, LearningInterface, MoveItInterface
Direct Known Subclasses:
FetchItComponent

public class FetchComponent extends MoveItComponent implements FetchInterface
  • 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 class MoveItComponent
    • additionalUsageInfo

      protected List<org.apache.commons.cli.Option> additionalUsageInfo()
      Description copied from class: DiarcComponent
      Command line options available in sub-class. This should be paired with a parseArgs implementation.
      Overrides:
      additionalUsageInfo in class MoveItComponent
      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 class MoveItComponent
    • pointHeadTo

      public boolean pointHeadTo(MemoryObject target_object)
      Description copied from interface: FetchInterface
      Point head in direction of target object in base_link coordinate frame.
      Specified by:
      pointHeadTo in interface FetchInterface
      Returns:
    • pointHeadTo

      public boolean pointHeadTo(Symbol objectRef)
      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 interface FetchInterface
      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 interface FetchInterface
      Returns:
    • setTorsoPosition

      public boolean setTorsoPosition(double position)
      Description copied from interface: FetchInterface
      Move the torso to desired joint position.
      Specified by:
      setTorsoPosition in interface FetchInterface
      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

      public Justification lookAround()
      Specified by:
      lookAround in interface FetchInterface
    • moveTo

      public Justification moveTo(String group_name, Symbol objectRef)
      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 interface ArmInterface
      Overrides:
      moveTo in class MoveItComponent
      Returns:
      true on success, false on failure. This function blocks.
    • checkGrasping

      public List<Map<Variable,Symbol>> checkGrasping(Term graspingTerm)
      Specified by:
      checkGrasping in interface FetchInterface
    • moveObject

      public Justification moveObject(Symbol objectRef, String arm, String direction)
      Specified by:
      moveObject in interface FetchInterface
    • look

      public Justification look(String direction)
      Specified by:
      look in interface FetchInterface
    • getChargeLevel

      public float getChargeLevel()
      Description copied from interface: FetchInterface
      Gets the charge level of the fetch
      Specified by:
      getChargeLevel in interface FetchInterface
      Returns:
      The charge level of the fest (between 0-1) or -1 if battery state is null (likely not being published)
    • getBreakerState

      public FetchBreakerStates getBreakerState(String breakerName)
      Description copied from interface: FetchInterface
      Gets the specified breaker state.
      Specified by:
      getBreakerState in interface FetchInterface
      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

      public FetchBreakerStates setBreakerState(String breakerName, boolean state)
      Description copied from interface: FetchInterface
      Sends a breaker command request to set the given breaker to the desired state.
      Specified by:
      setBreakerState in interface FetchInterface
      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.