Class PR2BaseComponent

java.lang.Object
edu.tufts.hrilab.diarc.DiarcComponent
edu.tufts.hrilab.pr2.PR2BaseComponent
All Implemented Interfaces:
NavigationInterface, OrientationInterface, VelocityInterface, PR2BaseInterface

public class PR2BaseComponent extends DiarcComponent implements PR2BaseInterface
  • Constructor Details

    • PR2BaseComponent

      public PR2BaseComponent()
      PR2BaseComponent constructor.
  • 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 DiarcComponent
    • 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 DiarcComponent
      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 DiarcComponent
    • moveTo

      public long moveTo(double xdest, double ydest, double quat_x, double quat_y, double quat_z, double quat_w)
      Move to a global location.
      Specified by:
      moveTo in interface PR2BaseInterface
      Parameters:
      xdest - the x-coordinate of the destination
      ydest - the y-coordinate of the destination
      quat_x - x quaternion value
      quat_y - y quaternion value
      quat_z - z quaternion value
      quat_w - w quaternion value
      Returns:
      an identifying timestamp for the move action
    • moveTo

      public long moveTo(double xdest, double ydest)
      Move to a global location.
      Specified by:
      moveTo in interface NavigationInterface
      Parameters:
      xdest - the x-coordinate of the destination
      ydest - the y-coordinate of the destination
      Returns:
      an identifying timestamp for the move action
    • moveDist

      public long moveDist(double dist)
      Move forward a specified distance.
      Specified by:
      moveDist in interface NavigationInterface
      Parameters:
      dist - the distance (in meters) to move
      Returns:
      an identifying timestamp for the move action
    • checkMotion

      public ActionStatus checkMotion(long aid)
      Check status of current Motion. Soon this will be obsoleted, as the motion commands will notify Action of their completions.
      Specified by:
      checkMotion in interface NavigationInterface
      Specified by:
      checkMotion in interface OrientationInterface
      Parameters:
      aid - the identifying timestamp of the action to check
      Returns:
      the status found for the indicated action
    • cancelMotion

      public boolean cancelMotion(long aid)
      Cancel current Motion.
      Specified by:
      cancelMotion in interface NavigationInterface
      Specified by:
      cancelMotion in interface OrientationInterface
      Parameters:
      aid - the identifying timestamp of the action to cancel
      Returns:
      true if action was canceled, false otherwise (i.e., if that action ID was not active)
    • turnTo

      public long turnTo(double tdest)
      Turn to a global heading.
      Specified by:
      turnTo in interface OrientationInterface
      Parameters:
      tdest - the global heading (in radians) to which to turn
      Returns:
      an identifying timestamp for the turn action
    • turnDist

      public long turnDist(double dist)
      Turn a specified distance.
      Specified by:
      turnDist in interface OrientationInterface
      Parameters:
      dist - the distance (in radians) to turn
      Returns:
      an identifying timestamp for the turn action
    • getTV

      public double getTV()
      Get translational velocity.
      Specified by:
      getTV in interface VelocityInterface
      Returns:
      the most recent TV reading (m/sec).
    • getRV

      public double getRV()
      Get rotational velocity.
      Specified by:
      getRV in interface VelocityInterface
      Returns:
      the most recent RV reading (rad/sec).
    • getVels

      public double[] getVels()
      Get translational and rotational velocity.
      Specified by:
      getVels in interface VelocityInterface
      Returns:
      the most recent velocity readings (m/sec and rad/sec).
    • getDefaultVels

      public double[] getDefaultVels()
      Get the default velocities used by VelocityComponent functions.
      Specified by:
      getDefaultVels in interface VelocityInterface
      Returns:
      the default velocities (m/sec and rad/sec).
    • stop

      public void stop()
      Stop.
      Specified by:
      stop in interface VelocityInterface
    • setTV

      public boolean setTV(double tv)
      Set translational velocity.
      Specified by:
      setTV in interface VelocityInterface
      Parameters:
      tv - the new TV (m/sec)
      Returns:
      true if there's nothing in front of the robot, false otherwise.
    • setRV

      public boolean setRV(double rv)
      Set rotational velocity.
      Specified by:
      setRV in interface VelocityInterface
      Parameters:
      rv - the new RV (rad/sec)
      Returns:
      true if there's nothing on that side, false otherwise.
    • setVels

      public boolean setVels(double tv, double rv)
      Set both velocities.
      Specified by:
      setVels in interface VelocityInterface
      Parameters:
      tv - the new TV (m/sec)
      rv - the new RV (rad/sec)
      Returns:
      true if there's nothing in front of the robot, false otherwise.
    • getPoseGlobalQuat

      public double[] getPoseGlobalQuat()
      Description copied from interface: PR2BaseInterface
      Alternative version of getPoseGlobal that returns x-y location as well as quaternion orientation (x, y, quat_x, quat_y, quat_z, quat_w).
      Specified by:
      getPoseGlobalQuat in interface PR2BaseInterface
      Returns: