Class HeadTrajControllerPointHeadAction

java.lang.Object
edu.tufts.hrilab.diarcros.pr2.HeadTrajControllerPointHeadAction

public class HeadTrajControllerPointHeadAction extends Object
  • Constructor Details

    • HeadTrajControllerPointHeadAction

      public HeadTrajControllerPointHeadAction()
  • Method Details

    • waitForNode

      public void waitForNode()
    • waitForNode

      public boolean waitForNode(long timeout)
      Wait for node to be ready, with timeout. If timeout is reached and node is not ready, will return false.
      Parameters:
      timeout - how long to wait in seconds
      Returns:
    • isNodeReady

      public boolean isNodeReady()
      Is node connected to ROS and ready.
      Returns:
    • getHeadTrajControllerCommand

      public edu.tufts.hrilab.diarcros.msg.trajectory_msgs.JointTrajectory getHeadTrajControllerCommand()
    • getRosout

      public edu.tufts.hrilab.diarcros.msg.rosgraph_msgs.Log getRosout()
    • sendTf

      public void sendTf(edu.tufts.hrilab.diarcros.msg.tf2_msgs.TFMessage msg)
    • sendHeadTrajControllerState

      public void sendHeadTrajControllerState(edu.tufts.hrilab.diarcros.msg.pr2_controllers_msgs.JointTrajectoryControllerState msg)
    • sendTfStatic

      public void sendTfStatic(edu.tufts.hrilab.diarcros.msg.tf2_msgs.TFMessage msg)
    • sendClock

      public void sendClock(edu.tufts.hrilab.diarcros.msg.rosgraph_msgs.Clock msg)
    • callHeadTrajControllerPointHeadActionSetLoggerLevel

      public boolean callHeadTrajControllerPointHeadActionSetLoggerLevel(edu.tufts.hrilab.diarcros.msg.roscpp.SetLoggerLevelRequest request, edu.tufts.hrilab.diarcros.msg.roscpp.SetLoggerLevelResponse response)
    • callHeadTrajControllerPointHeadActionGetLoggers

      public boolean callHeadTrajControllerPointHeadActionGetLoggers(edu.tufts.hrilab.diarcros.msg.roscpp.GetLoggersRequest request, edu.tufts.hrilab.diarcros.msg.roscpp.GetLoggersResponse response)
    • cancelAllGoals

      public void cancelAllGoals()
    • cancelGoal

      public void cancelGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelGoalsAtAndBeforeTime

      public void cancelGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getResult

      public pr2_controllers_msgs.PointHeadResult getResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getState

      public org.ros.actionlib.state.SimpleClientGoalState getState()
    • sendGoal

      public void sendGoal(edu.tufts.hrilab.diarcros.msg.pr2_controllers_msgs.PointHeadGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForResult

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

      public boolean waitForResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForServer

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

      public boolean waitForServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException