Class MoveBaseNode

java.lang.Object
edu.tufts.hrilab.diarcros.common.MoveBaseNode

public class MoveBaseNode extends Object
  • Constructor Details

    • MoveBaseNode

      public MoveBaseNode()
    • MoveBaseNode

      public MoveBaseNode(RosConfiguration rc)
  • Method Details

    • waitForNode

      public void waitForNode()
    • getMoveBaseGoal

      public edu.tufts.hrilab.diarcros.msg.move_base_msgs.MoveBaseActionGoal getMoveBaseGoal()
    • getMoveBaseNodeCurrentGoal

      public edu.tufts.hrilab.diarcros.msg.geometry_msgs.PoseStamped getMoveBaseNodeCurrentGoal()
    • sendMoveBaseSimpleGoal

      public void sendMoveBaseSimpleGoal(edu.tufts.hrilab.diarcros.msg.geometry_msgs.PoseStamped msg)
    • sendCmdVelocity

      public void sendCmdVelocity(edu.tufts.hrilab.diarcros.msg.geometry_msgs.Twist msg)
    • cancelAllMoveBaseGoals

      public void cancelAllMoveBaseGoals()
    • cancelMoveBaseGoal

      public void cancelMoveBaseGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelMoveBaseGoalsAtAndBeforeTime

      public void cancelMoveBaseGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getMoveBaseResult

      public move_base_msgs.MoveBaseResult getMoveBaseResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getMoveBaseState

      public org.ros.actionlib.state.SimpleClientGoalState getMoveBaseState()
    • sendMoveBaseGoal

      public void sendMoveBaseGoal(edu.tufts.hrilab.diarcros.msg.move_base_msgs.MoveBaseGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForMoveBaseResult

      public void waitForMoveBaseResult() throws InterruptedException
      Throws:
      InterruptedException
    • waitForMoveBaseResult

      public boolean waitForMoveBaseResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForMoveBaseServer

      public void waitForMoveBaseServer() throws InterruptedException
      Throws:
      InterruptedException
    • waitForMoveBaseServer

      public boolean waitForMoveBaseServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • callClearCostmaps

      public boolean callClearCostmaps(edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyRequest request, edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyResponse response)