Class PivotToDynamicAbsoluteCmd<T extends TagalongSubsystemBase & PivotAugment>

All Implemented Interfaces:
Sendable

Command that continuously and optimally moves the pivot towards the supplied goal rotation
  • Constructor Details

    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      id - Integer ID of the pivot microsystem inside the Tagalong Subsystem
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
      holdPositionAfter - If the pivot should hold position when the command completes
      maxVelocityRPS - Maximum velocity for the pivot during this command
      startSupplier - BooleanSupplier condition for movement to start, defaults to pivot::isSafeToMove
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS, BooleanSupplier startSupplier)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
      holdPositionAfter - If the pivot should hold position when the command completes
      maxVelocityRPS - Maximum velocity for the pivot during this command
      startSupplier - BooleanSupplier condition for movement to start, defaults to pivot::isSafeToMove
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      id - Integer ID of the pivot microsystem inside the Tagalong Subsystem
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
      holdPositionAfter - If the pivot should hold position when the command completes
      maxVelocityRPS - Maximum velocity for the pivot during this command
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter, double maxVelocityRPS)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
      holdPositionAfter - If the pivot should hold position when the command completes
      maxVelocityRPS - Maximum velocity for the pivot during this command
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      id - Integer ID of the pivot microsystem inside the Tagalong Subsystem
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
      holdPositionAfter - If the pivot should hold position when the command completes
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot, boolean holdPositionAfter)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
      holdPositionAfter - If the pivot should hold position when the command completes command
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(int id, T pivot, DoubleSupplier goalSupplierRot)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      id - Integer ID of the pivot microsystem inside the Tagalong Subsystem
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
    • PivotToDynamicAbsoluteCmd

      public PivotToDynamicAbsoluteCmd(T pivot, DoubleSupplier goalSupplierRot)
      Continuously move to the double suppliers target position. The function is continuous, it has no end condition, so the user must interrupt the command or decorate the command with an end condition. Useful for dynamic movements that are dependent on sensor readings, field conditions, or driver configurations.
      Parameters:
      pivot - Tagalong Subsystem containing an pivot microsystem
      goalSupplierRot - DoubleSupplier for the pivot rotation
  • Method Details