public async static Task MoveJointsSupervised( [InputPin(PropertyMode = PropertyMode.Default, Editor = "JointValues")] JointValuesProperty target, [InputPin(PropertyMode = PropertyMode.Default)] bool collisionChecking = true, [InputPin(PropertyMode = PropertyMode.Default)] double velocityScaling = 1, [InputPin(PropertyMode = PropertyMode.Default)] double sampleResolution = 0.05, [InputPin(PropertyMode = PropertyMode.Default)] bool cacheResult = true, CancellationToken cancel = default(CancellationToken) ) { if (target == null) { throw new ArgumentNullException(nameof(target), "Required property 'target' for MoveJ module was not specified."); } var targetJointValues = await ResolveProperty(target); using (var group = MotionService.CreateMoveGroupForJointSet(targetJointValues.JointSet)) { group.SampleResolution = sampleResolution; using (var client = group.MoveJointsSupervisedAsync(targetJointValues, velocityScaling, collisionChecking, null, cancel)) { await HandleStepwiseMotions(client, group); } } }
private static async Task <JointValues> ResolveProperty(JointValuesProperty p) { if (p == null) { return(null); } if (p.Source == PropertySource.Constant) { return(p.Value); } return((await worldViewService.GetJointValuesByPath(p.Path)).Value.ToJointValues()); }
public async static Task MovePoseWaypointsSupervised( [InputPin(PropertyMode = PropertyMode.Never)] IEnumerable <Pose> waypoints = null, [InputPin(PropertyMode = PropertyMode.Default)] string endEffectorName = null, [InputPin(PropertyMode = PropertyMode.Default)] bool collisionChecking = false, [InputPin(PropertyMode = PropertyMode.Default)] double velocityScaling = 1, [InputPin(PropertyMode = PropertyMode.Default)] double sampleResolution = 0.05, [InputPin(PropertyMode = PropertyMode.Default, Editor = "JointValues")] JointValuesProperty seed = null, [InputPin(PropertyMode = PropertyMode.Default)] bool cacheResult = true, CancellationToken cancel = default(CancellationToken) ) { if (waypoints == null) { throw new ArgumentNullException("Required property 'waypoints' for MovePoseLinearWaypointsSupervised module was not specified.", nameof(waypoints)); } if (waypoints.ToList().Count == 0) { throw new ArgumentException("Required property 'waypoints' is empty.", nameof(waypoints)); } var seedValues = await ResolveProperty(seed); var endEffector = MotionService.QueryAvailableEndEffectors().FirstOrDefault(x => x.Name == endEffectorName); if (endEffector == null) { throw new Exception($"EndEffector '{endEffectorName}' not available."); } CartesianPath path = new CartesianPath(waypoints); using (var group = MotionService.CreateMoveGroup(endEffector.MoveGroupName, endEffector.Name)) { if (seed == null) { seedValues = group.CurrentJointPositions; } group.SampleResolution = sampleResolution; group.CollisionCheck = collisionChecking; group.VelocityScaling = velocityScaling; using (var client = group.GetEndEffector(endEffectorName).MoveCartesianPathSupervisedAsync(path, seedValues, cancel)) { await HandleStepwiseMotions(client, group); } } }
public async static Task MoveJointsCollisionFree( [InputPin(PropertyMode = PropertyMode.Default, Editor = "JointValues")] JointValuesProperty target, [InputPin(PropertyMode = PropertyMode.Default)] string moveGroupName = null, [InputPin(PropertyMode = PropertyMode.Default)] double velocityScaling = 1, [InputPin(PropertyMode = PropertyMode.Default)] double sampleResolution = 0.05, [InputPin(PropertyMode = PropertyMode.Default)] bool cacheResult = true, CancellationToken cancel = default(CancellationToken) ) { if (target == null) { throw new ArgumentNullException(nameof(target), "Required property 'target' for MoveJointsCollisionFree module was not specified."); } var targetJointValues = await ResolveProperty(target); using (var group = MotionService.CreateMoveGroup(moveGroupName)) { await group.MoveJointsCollisionFreeAsync(targetJointValues, velocityScaling, sampleResolution, cancel); } }
public async static Task MovePoseCollisionFreeSupervised( [InputPin(PropertyMode = PropertyMode.Default, Editor = "Pose")] PoseProperty target, [InputPin(PropertyMode = PropertyMode.Default)] string endEffectorName = null, [InputPin(PropertyMode = PropertyMode.Default)] double velocityScaling = 1, [InputPin(PropertyMode = PropertyMode.Default)] double sampleResolution = 0.05, [InputPin(PropertyMode = PropertyMode.Default, Editor = "JointValues")] JointValuesProperty seed = null, [InputPin(PropertyMode = PropertyMode.Default)] bool cacheResult = true, CancellationToken cancel = default(CancellationToken) ) { if (target == null) { throw new ArgumentNullException(nameof(target), "Required property 'target' for MovePoseCollisionFreeSupervised module was not specified."); } var endEffector = MotionService.QueryAvailableEndEffectors().FirstOrDefault(x => x.Name == endEffectorName); if (endEffector == null) { throw new Exception($"EndEffector '{endEffectorName}' not available."); } var targetPose = await ResolveProperty(target); var seedValues = await ResolveProperty(seed); using (var group = MotionService.CreateMoveGroup(endEffector.MoveGroupName, endEffector.Name)) { if (seed == null) { seedValues = group.CurrentJointPositions; } group.SampleResolution = sampleResolution; using (var client = group.GetEndEffector(endEffector.Name).MovePoseCollisionFreeSupervisedAsync(targetPose, seedValues, cancel)) { await HandleStepwiseMotions(client, group); } } }