Package edu.tufts.hrilab.diarcros.moveit
Class MoveGroup
java.lang.Object
edu.tufts.hrilab.diarcros.moveit.MoveGroup
- All Implemented Interfaces:
GenericMoveGroup
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionboolean
callApplyPlanningScene
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ApplyPlanningSceneRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.ApplyPlanningSceneResponse response) boolean
callCheckStateValidity
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetStateValidityRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetStateValidityResponse response) boolean
callClearOctomap
(edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyRequest request, edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyResponse response) boolean
callComputeCartesianPath
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetCartesianPathRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetCartesianPathResponse response) boolean
callComputeFk
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionFKRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionFKResponse response) boolean
callComputeIk
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionIKRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionIKResponse response) boolean
callExecuteKinematicPath
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteKnownTrajectoryRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteKnownTrajectoryResponse response) boolean
callGetPlannerParams
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlannerParamsRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlannerParamsResponse response) boolean
callGetPlanningScene
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneResponse response) boolean
callMoveGroupGetLoggers
(edu.tufts.hrilab.diarcros.msg.roscpp.GetLoggersRequest request, edu.tufts.hrilab.diarcros.msg.roscpp.GetLoggersResponse response) boolean
callMoveGroupLoadMap
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.LoadMapRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.LoadMapResponse response) boolean
callMoveGroupOmplSetParameters
(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response) boolean
callMoveGroupPlanExecutionSetParameters
(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response) boolean
callMoveGroupPlanningSceneMonitorSetParameters
(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response) boolean
callMoveGroupSaveMap
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.SaveMapRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.SaveMapResponse response) boolean
callMoveGroupSenseForPlanSetParameters
(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response) boolean
callMoveGroupSetLoggerLevel
(edu.tufts.hrilab.diarcros.msg.roscpp.SetLoggerLevelRequest request, edu.tufts.hrilab.diarcros.msg.roscpp.SetLoggerLevelResponse response) boolean
callMoveGroupTrajectoryExecutionSetParameters
(edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureRequest request, edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ReconfigureResponse response) boolean
callPlanKinematicPath
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanResponse response) boolean
callQueryPlannerInterface
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.QueryPlannerInterfacesRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.QueryPlannerInterfacesResponse response) boolean
callSetPlannerParams
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.SetPlannerParamsRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.SetPlannerParamsResponse response) void
void
void
void
void
void
void
cancelControlMsgsFollowJointTrajectoryGoalsAtAndBeforeTime
(edu.tufts.hrilab.diarcros.msg.Time time) void
void
cancelControlMsgsGripperCommandGoalsAtAndBeforeTime
(edu.tufts.hrilab.diarcros.msg.Time time) void
void
cancelMoveitMsgsExecuteTrajectoryGoalsAtAndBeforeTime
(edu.tufts.hrilab.diarcros.msg.Time time) void
void
cancelMoveitMsgsMoveGroupGoalsAtAndBeforeTime
(edu.tufts.hrilab.diarcros.msg.Time time) void
void
cancelMoveitMsgsPlaceGoalsAtAndBeforeTime
(edu.tufts.hrilab.diarcros.msg.Time time) boolean
executeKinematicPath
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.RobotTrajectory rt) control_msgs.FollowJointTrajectoryResult
org.ros.actionlib.state.SimpleClientGoalState
control_msgs.GripperCommandResult
org.ros.actionlib.state.SimpleClientGoalState
edu.tufts.hrilab.diarcros.msg.Time
edu.tufts.hrilab.diarcros.msg.visualization_msgs.MarkerArray
edu.tufts.hrilab.diarcros.msg.moveit_msgs.DisplayTrajectory
edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.ConfigDescription
edu.tufts.hrilab.diarcros.msg.dynamic_reconfigure.Config
moveit_msgs.ExecuteTrajectoryResult
org.ros.actionlib.state.SimpleClientGoalState
moveit_msgs.MoveGroupResult
org.ros.actionlib.state.SimpleClientGoalState
moveit_msgs.PlaceResult
org.ros.actionlib.state.SimpleClientGoalState
boolean
void
sendAttachedCollisionObject
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.AttachedCollisionObject msg) void
sendClock
(edu.tufts.hrilab.diarcros.msg.rosgraph_msgs.Clock msg) void
sendCollisionObject
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.CollisionObject msg) void
sendControlMsgsFollowJointTrajectoryGoal
(edu.tufts.hrilab.diarcros.msg.control_msgs.FollowJointTrajectoryGoal goal) void
sendControlMsgsGripperCommandGoal
(edu.tufts.hrilab.diarcros.msg.control_msgs.GripperCommandGoal goal) void
sendJointStates
(edu.tufts.hrilab.diarcros.msg.sensor_msgs.JointState msg) void
sendMoveitMsgsExecuteTrajectoryGoal
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteTrajectoryGoal goal) void
sendMoveitMsgsMoveGroupGoal
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.MoveGroupGoal goal) void
sendMoveitMsgsPlaceGoal
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlaceGoal goal) void
sendPlanningScene
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene msg) void
sendPlanningSceneWorld
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningSceneWorld msg) void
sendPointCloud
(edu.tufts.hrilab.diarcros.msg.sensor_msgs.PointCloud2 msg) void
sendTf
(edu.tufts.hrilab.diarcros.msg.tf2_msgs.TFMessage msg) void
sendTfStatic
(edu.tufts.hrilab.diarcros.msg.tf2_msgs.TFMessage msg) void
sendTrajectoryExecutionEvent
(edu.tufts.hrilab.diarcros.msg.std_msgs.String msg) void
shutdown()
void
boolean
waitForControlMsgsFollowJointTrajectoryResult
(long timeout, TimeUnit units) void
boolean
waitForControlMsgsFollowJointTrajectoryServer
(long timeout, TimeUnit units) void
boolean
waitForControlMsgsGripperCommandResult
(long timeout, TimeUnit units) void
boolean
waitForControlMsgsGripperCommandServer
(long timeout, TimeUnit units) void
boolean
waitForMoveitMsgsExecuteTrajectoryResult
(long timeout, TimeUnit units) void
boolean
waitForMoveitMsgsExecuteTrajectoryServer
(long timeout, TimeUnit units) void
boolean
waitForMoveitMsgsMoveGroupResult
(long timeout, TimeUnit units) void
boolean
waitForMoveitMsgsMoveGroupServer
(long timeout, TimeUnit units) void
boolean
waitForMoveitMsgsPlaceResult
(long timeout, TimeUnit units) void
boolean
waitForMoveitMsgsPlaceServer
(long timeout, TimeUnit units) void
-
Constructor Details
-
MoveGroup
-
MoveGroup
public MoveGroup()
-
-
Method Details
-
getMoveGroupRosVersion
- Specified by:
getMoveGroupRosVersion
in interfaceGenericMoveGroup
-
shutdown
public void shutdown()- Specified by:
shutdown
in interfaceGenericMoveGroup
-
isConnected
public boolean isConnected()- Specified by:
isConnected
in interfaceGenericMoveGroup
-
waitForNode
public void waitForNode()- Specified by:
waitForNode
in interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
sendPlanningScene
public void sendPlanningScene(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene msg) - Specified by:
sendPlanningScene
in interfaceGenericMoveGroup
-
sendCollisionObject
public void sendCollisionObject(edu.tufts.hrilab.diarcros.msg.moveit_msgs.CollisionObject msg) - Specified by:
sendCollisionObject
in interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
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 interfaceGenericMoveGroup
-
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
- Throws:
InterruptedException
-
waitForMoveitMsgsExecuteTrajectoryResult
public boolean waitForMoveitMsgsExecuteTrajectoryResult(long timeout, TimeUnit units) throws InterruptedException - Throws:
InterruptedException
-
waitForMoveitMsgsExecuteTrajectoryServer
- 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
- Throws:
InterruptedException
-
waitForMoveitMsgsMoveGroupResult
public boolean waitForMoveitMsgsMoveGroupResult(long timeout, TimeUnit units) throws InterruptedException - Throws:
InterruptedException
-
waitForMoveitMsgsMoveGroupServer
- 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
- Throws:
InterruptedException
-
waitForMoveitMsgsPlaceResult
public boolean waitForMoveitMsgsPlaceResult(long timeout, TimeUnit units) throws InterruptedException - Throws:
InterruptedException
-
waitForMoveitMsgsPlaceServer
- 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
- Throws:
InterruptedException
-
waitForControlMsgsFollowJointTrajectoryResult
public boolean waitForControlMsgsFollowJointTrajectoryResult(long timeout, TimeUnit units) throws InterruptedException - Throws:
InterruptedException
-
waitForControlMsgsFollowJointTrajectoryServer
- 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
- Throws:
InterruptedException
-
waitForControlMsgsGripperCommandResult
public boolean waitForControlMsgsGripperCommandResult(long timeout, TimeUnit units) throws InterruptedException - Throws:
InterruptedException
-
waitForControlMsgsGripperCommandServer
- 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 interfaceGenericMoveGroup
- 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 interfaceGenericMoveGroup
-
sendPointCloud
public void sendPointCloud(edu.tufts.hrilab.diarcros.msg.sensor_msgs.PointCloud2 msg) - Specified by:
sendPointCloud
in interfaceGenericMoveGroup
-