Class MoveGroup

java.lang.Object
edu.tufts.hrilab.diarcros.moveit.MoveGroup
All Implemented Interfaces:
GenericMoveGroup

public class MoveGroup extends Object implements GenericMoveGroup
  • Constructor Details

    • MoveGroup

      public MoveGroup(String namespace, Map<String,String> remappings)
    • MoveGroup

      public MoveGroup()
  • Method Details

    • getMoveGroupRosVersion

      public String getMoveGroupRosVersion()
      Specified by:
      getMoveGroupRosVersion in interface GenericMoveGroup
    • shutdown

      public void shutdown()
      Specified by:
      shutdown in interface GenericMoveGroup
    • isConnected

      public boolean isConnected()
      Specified by:
      isConnected in interface GenericMoveGroup
    • waitForNode

      public void waitForNode()
      Specified by:
      waitForNode in interface GenericMoveGroup
    • getCurrentTime

      public edu.tufts.hrilab.diarcros.msg.Time getCurrentTime()
    • getMoveGroupSenseForPlanParameterUpdates

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config getMoveGroupSenseForPlanParameterUpdates()
    • getMoveGroupPlanningSceneMonitorParameterDescriptions

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription getMoveGroupPlanningSceneMonitorParameterDescriptions()
    • getMoveGroupPlanExecutionParameterDescriptions

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription getMoveGroupPlanExecutionParameterDescriptions()
    • getMoveGroupDisplayPlannedPath

      public edu.tufts.hrilab.diarcros.msg.moveit_msgs.DisplayTrajectory getMoveGroupDisplayPlannedPath()
    • getMoveGroupTrajectoryExecutionParameterDescriptions

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription getMoveGroupTrajectoryExecutionParameterDescriptions()
    • getMoveGroupOmplParameterUpdates

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config getMoveGroupOmplParameterUpdates()
    • getMoveGroupOmplParameterDescriptions

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription getMoveGroupOmplParameterDescriptions()
    • getMoveGroupTrajectoryExecutionParameterUpdates

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config getMoveGroupTrajectoryExecutionParameterUpdates()
    • getMoveGroupPlanExecutionParameterUpdates

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config getMoveGroupPlanExecutionParameterUpdates()
    • getMoveGroupPlanningSceneMonitorParameterUpdates

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config getMoveGroupPlanningSceneMonitorParameterUpdates()
    • getMoveGroupSenseForPlanParameterDescriptions

      public edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription getMoveGroupSenseForPlanParameterDescriptions()
    • getMoveGroupDisplayContacts

      public edu.tufts.hrilab.diarcros.msg.visualization_msgs.MarkerArray getMoveGroupDisplayContacts()
    • getMoveGroupMonitoredPlanningScene

      public edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene getMoveGroupMonitoredPlanningScene()
    • sendTf

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

      public void sendJointStates(edu.tufts.hrilab.diarcros.msg.sensor_msgs.JointState msg)
    • sendTrajectoryExecutionEvent

      public void sendTrajectoryExecutionEvent(edu.tufts.hrilab.diarcros.msg.std_msgs.String msg)
    • sendTfStatic

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

      public void sendPlanningSceneWorld(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningSceneWorld msg)
    • sendAttachedCollisionObject

      public void sendAttachedCollisionObject(edu.tufts.hrilab.diarcros.msg.moveit_msgs.AttachedCollisionObject msg)
      Specified by:
      sendAttachedCollisionObject in interface GenericMoveGroup
    • sendPlanningScene

      public void sendPlanningScene(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene msg)
      Specified by:
      sendPlanningScene in interface GenericMoveGroup
    • sendCollisionObject

      public void sendCollisionObject(edu.tufts.hrilab.diarcros.msg.moveit_msgs.CollisionObject msg)
      Specified by:
      sendCollisionObject in interface GenericMoveGroup
    • sendClock

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

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

      public boolean callMoveGroupPlanningSceneMonitorSetParameters(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response)
    • callGetPlanningScene

      public boolean callGetPlanningScene(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneResponse response)
      Specified by:
      callGetPlanningScene in interface GenericMoveGroup
    • callMoveGroupPlanExecutionSetParameters

      public boolean callMoveGroupPlanExecutionSetParameters(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response)
    • callCheckStateValidity

      public boolean callCheckStateValidity(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetStateValidityRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetStateValidityResponse response)
    • callQueryPlannerInterface

      public boolean callQueryPlannerInterface(edu.tufts.hrilab.diarcros.msg.moveit_msgs.QueryPlannerInterfacesRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.QueryPlannerInterfacesResponse response)
    • callPlanKinematicPath

      public boolean callPlanKinematicPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanResponse response)
      Specified by:
      callPlanKinematicPath in interface GenericMoveGroup
    • callMoveGroupTrajectoryExecutionSetParameters

      public boolean callMoveGroupTrajectoryExecutionSetParameters(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response)
    • callMoveGroupSaveMap

      public boolean callMoveGroupSaveMap(edu.tufts.hrilab.diarcros.msg.moveit_msgs.SaveMapRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.SaveMapResponse response)
    • callApplyPlanningScene

      public boolean callApplyPlanningScene(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ApplyPlanningSceneRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.ApplyPlanningSceneResponse response)
    • callGetPlannerParams

      public boolean callGetPlannerParams(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlannerParamsRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlannerParamsResponse response)
    • callMoveGroupGetLoggers

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

      public boolean callClearOctomap(edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyRequest request, edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyResponse response)
      Specified by:
      callClearOctomap in interface GenericMoveGroup
    • callMoveGroupOmplSetParameters

      public boolean callMoveGroupOmplSetParameters(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response)
    • callMoveGroupLoadMap

      public boolean callMoveGroupLoadMap(edu.tufts.hrilab.diarcros.msg.moveit_msgs.LoadMapRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.LoadMapResponse response)
    • callComputeCartesianPath

      public boolean callComputeCartesianPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetCartesianPathRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetCartesianPathResponse response)
      Specified by:
      callComputeCartesianPath in interface GenericMoveGroup
    • callMoveGroupSenseForPlanSetParameters

      public boolean callMoveGroupSenseForPlanSetParameters(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response)
    • callComputeIk

      public boolean callComputeIk(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionIKRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionIKResponse response)
      Specified by:
      callComputeIk in interface GenericMoveGroup
    • callComputeFk

      public boolean callComputeFk(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionFKRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionFKResponse response)
      Specified by:
      callComputeFk in interface GenericMoveGroup
    • callSetPlannerParams

      public boolean callSetPlannerParams(edu.tufts.hrilab.diarcros.msg.moveit_msgs.SetPlannerParamsRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.SetPlannerParamsResponse response)
    • cancelAllMoveitMsgsExecuteTrajectoryGoals

      public void cancelAllMoveitMsgsExecuteTrajectoryGoals()
    • cancelMoveitMsgsExecuteTrajectoryGoal

      public void cancelMoveitMsgsExecuteTrajectoryGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelMoveitMsgsExecuteTrajectoryGoalsAtAndBeforeTime

      public void cancelMoveitMsgsExecuteTrajectoryGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getMoveitMsgsExecuteTrajectoryResult

      public moveit_msgs.ExecuteTrajectoryResult getMoveitMsgsExecuteTrajectoryResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getMoveitMsgsExecuteTrajectoryState

      public org.ros.actionlib.state.SimpleClientGoalState getMoveitMsgsExecuteTrajectoryState()
    • sendMoveitMsgsExecuteTrajectoryGoal

      public void sendMoveitMsgsExecuteTrajectoryGoal(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteTrajectoryGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForMoveitMsgsExecuteTrajectoryResult

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

      public boolean waitForMoveitMsgsExecuteTrajectoryResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForMoveitMsgsExecuteTrajectoryServer

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

      public boolean waitForMoveitMsgsExecuteTrajectoryServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • cancelAllMoveitMsgsMoveGroupGoals

      public void cancelAllMoveitMsgsMoveGroupGoals()
    • cancelMoveitMsgsMoveGroupGoal

      public void cancelMoveitMsgsMoveGroupGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelMoveitMsgsMoveGroupGoalsAtAndBeforeTime

      public void cancelMoveitMsgsMoveGroupGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getMoveitMsgsMoveGroupResult

      public moveit_msgs.MoveGroupResult getMoveitMsgsMoveGroupResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getMoveitMsgsMoveGroupState

      public org.ros.actionlib.state.SimpleClientGoalState getMoveitMsgsMoveGroupState()
    • sendMoveitMsgsMoveGroupGoal

      public void sendMoveitMsgsMoveGroupGoal(edu.tufts.hrilab.diarcros.msg.moveit_msgs.MoveGroupGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForMoveitMsgsMoveGroupResult

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

      public boolean waitForMoveitMsgsMoveGroupResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForMoveitMsgsMoveGroupServer

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

      public boolean waitForMoveitMsgsMoveGroupServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • cancelAllMoveitMsgsPlaceGoals

      public void cancelAllMoveitMsgsPlaceGoals()
    • cancelMoveitMsgsPlaceGoal

      public void cancelMoveitMsgsPlaceGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelMoveitMsgsPlaceGoalsAtAndBeforeTime

      public void cancelMoveitMsgsPlaceGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getMoveitMsgsPlaceResult

      public moveit_msgs.PlaceResult getMoveitMsgsPlaceResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getMoveitMsgsPlaceState

      public org.ros.actionlib.state.SimpleClientGoalState getMoveitMsgsPlaceState()
    • sendMoveitMsgsPlaceGoal

      public void sendMoveitMsgsPlaceGoal(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlaceGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForMoveitMsgsPlaceResult

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

      public boolean waitForMoveitMsgsPlaceResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForMoveitMsgsPlaceServer

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

      public boolean waitForMoveitMsgsPlaceServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • cancelAllControlMsgsFollowJointTrajectoryGoals

      public void cancelAllControlMsgsFollowJointTrajectoryGoals()
    • cancelControlMsgsFollowJointTrajectoryGoal

      public void cancelControlMsgsFollowJointTrajectoryGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelControlMsgsFollowJointTrajectoryGoalsAtAndBeforeTime

      public void cancelControlMsgsFollowJointTrajectoryGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getControlMsgsFollowJointTrajectoryResult

      public control_msgs.FollowJointTrajectoryResult getControlMsgsFollowJointTrajectoryResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getControlMsgsFollowJointTrajectoryState

      public org.ros.actionlib.state.SimpleClientGoalState getControlMsgsFollowJointTrajectoryState()
    • sendControlMsgsFollowJointTrajectoryGoal

      public void sendControlMsgsFollowJointTrajectoryGoal(edu.tufts.hrilab.diarcros.msg.control_msgs.FollowJointTrajectoryGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForControlMsgsFollowJointTrajectoryResult

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

      public boolean waitForControlMsgsFollowJointTrajectoryResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForControlMsgsFollowJointTrajectoryServer

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

      public boolean waitForControlMsgsFollowJointTrajectoryServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • cancelAllControlMsgsGripperCommandGoals

      public void cancelAllControlMsgsGripperCommandGoals()
    • cancelControlMsgsGripperCommandGoal

      public void cancelControlMsgsGripperCommandGoal() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • cancelControlMsgsGripperCommandGoalsAtAndBeforeTime

      public void cancelControlMsgsGripperCommandGoalsAtAndBeforeTime(edu.tufts.hrilab.diarcros.msg.Time time)
    • getControlMsgsGripperCommandResult

      public control_msgs.GripperCommandResult getControlMsgsGripperCommandResult() throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • getControlMsgsGripperCommandState

      public org.ros.actionlib.state.SimpleClientGoalState getControlMsgsGripperCommandState()
    • sendControlMsgsGripperCommandGoal

      public void sendControlMsgsGripperCommandGoal(edu.tufts.hrilab.diarcros.msg.control_msgs.GripperCommandGoal goal) throws org.ros.exception.RosException
      Throws:
      org.ros.exception.RosException
    • waitForControlMsgsGripperCommandResult

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

      public boolean waitForControlMsgsGripperCommandResult(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • waitForControlMsgsGripperCommandServer

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

      public boolean waitForControlMsgsGripperCommandServer(long timeout, TimeUnit units) throws InterruptedException
      Throws:
      InterruptedException
    • executeKinematicPath

      public boolean executeKinematicPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.RobotTrajectory rt) throws InterruptedException, org.ros.exception.RosException
      Specified by:
      executeKinematicPath in interface GenericMoveGroup
      Throws:
      InterruptedException
      org.ros.exception.RosException
    • callExecuteKinematicPath

      public boolean callExecuteKinematicPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteKnownTrajectoryRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteKnownTrajectoryResponse response)
      Specified by:
      callExecuteKinematicPath in interface GenericMoveGroup
    • sendPointCloud

      public void sendPointCloud(edu.tufts.hrilab.diarcros.msg.sensor_msgs.PointCloud2 msg)
      Specified by:
      sendPointCloud in interface GenericMoveGroup