Package edu.tufts.hrilab.diarcros.moveit
Interface GenericMoveGroup
- All Known Implementing Classes:
MoveGroup
public interface GenericMoveGroup
-
Method Summary
Modifier and TypeMethodDescriptionboolean
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
callGetPlanningScene
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneResponse response) boolean
callPlanKinematicPath
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanResponse response) boolean
executeKinematicPath
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.RobotTrajectory rt) boolean
void
sendAttachedCollisionObject
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.AttachedCollisionObject msg) void
sendCollisionObject
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.CollisionObject msg) void
sendPlanningScene
(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene msg) void
sendPointCloud
(edu.tufts.hrilab.diarcros.msg.sensor_msgs.PointCloud2 msg) void
shutdown()
void
-
Method Details
-
getMoveGroupRosVersion
String getMoveGroupRosVersion() -
callComputeCartesianPath
boolean callComputeCartesianPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetCartesianPathRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetCartesianPathResponse response) -
callComputeFk
boolean callComputeFk(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionFKRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionFKResponse response) -
callComputeIk
boolean callComputeIk(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionIKRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPositionIKResponse response) -
callExecuteKinematicPath
boolean callExecuteKinematicPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteKnownTrajectoryRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.ExecuteKnownTrajectoryResponse response) -
callGetPlanningScene
boolean callGetPlanningScene(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetPlanningSceneResponse response) -
callPlanKinematicPath
boolean callPlanKinematicPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanRequest request, edu.tufts.hrilab.diarcros.msg.moveit_msgs.GetMotionPlanResponse response) -
executeKinematicPath
boolean executeKinematicPath(edu.tufts.hrilab.diarcros.msg.moveit_msgs.RobotTrajectory rt) throws InterruptedException, org.ros.exception.RosException - Throws:
InterruptedException
org.ros.exception.RosException
-
callClearOctomap
boolean callClearOctomap(edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyRequest request, edu.tufts.hrilab.diarcros.msg.std_srvs.EmptyResponse response) -
isConnected
boolean isConnected() -
sendAttachedCollisionObject
void sendAttachedCollisionObject(edu.tufts.hrilab.diarcros.msg.moveit_msgs.AttachedCollisionObject msg) -
sendCollisionObject
void sendCollisionObject(edu.tufts.hrilab.diarcros.msg.moveit_msgs.CollisionObject msg) -
sendPlanningScene
void sendPlanningScene(edu.tufts.hrilab.diarcros.msg.moveit_msgs.PlanningScene msg) -
sendPointCloud
void sendPointCloud(edu.tufts.hrilab.diarcros.msg.sensor_msgs.PointCloud2 msg) -
shutdown
void shutdown() -
waitForNode
void waitForNode()
-