From 4a6ea6bb9f1a11bb78375537bdd2543aa025b5fa Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Fri, 17 May 2024 16:20:46 -0400 Subject: [PATCH 1/9] add motion service code snippets --- services/motion/motion.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index ea947c10c2c..4ac3a9140b1 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -190,7 +190,7 @@ type PlanWithStatus struct { // // Move example: // -// motionService, err := motion.FromRobot(robot, "builtin") +// motionService, err := motion.FromRobot(machine, "builtin") // // // Assumes a gripper configured with name "my_gripper" on the machine // gripperName := gripper.Named("my_gripper") From a818285a8042243453ff2daa9b21d5ea0419342d Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Fri, 17 May 2024 16:58:13 -0400 Subject: [PATCH 2/9] add method descriptions --- services/motion/motion.go | 29 +++++++++++++++++++++++++++++ 1 file changed, 29 insertions(+) diff --git a/services/motion/motion.go b/services/motion/motion.go index 4ac3a9140b1..21c016c9a0d 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -295,6 +295,10 @@ type PlanWithStatus struct { // planStatuses, err := motionService.ListPlanStatuses(ctx, motion.ListPlanStatusesReq{}) type Service interface { resource.Resource + + // Move is the primary method to move multiple components or any object to a specified location. + // Given a destination pose and a component, Move constructs a kinematic chain from goal to destination, + // solves it while adhering to constraints, and executes the movement to avoid collisions with the machine itself and other known objects. Move( ctx context.Context, componentName resource.Name, @@ -303,14 +307,28 @@ type Service interface { constraints *motionplan.Constraints, extra map[string]interface{}, ) (bool, error) + + // MoveOnMap moves a base component to a destination Pose on a SLAM map and returns a unique ExecutionID. + // If the machine is already within PlanDeviationM of the goal, an error is returned. + // Monitor progress with `GetPlan()` and `ListPlanStatuses()`, and check the machine's position via the SLAM service. + // Designed for autonomous indoor navigation of rover bases. MoveOnMap( ctx context.Context, req MoveOnMapReq, ) (ExecutionID, error) + + // MoveOnGlobe moves a base component to a destination GPS point(latitude, longitude and returns a unique ExecutionID. + // If the machine is already within PlanDeviationM of the goal, an error is returned. + // This non-blocking method uses a movement sensor to verify the location of the base. + // You can monitor progress with `GetPlan()` and `ListPlanStatuses()`. Designed for autonomous GPS navigation of rover bases. MoveOnGlobe( ctx context.Context, req MoveOnGlobeReq, ) (ExecutionID, error) + + // GetPose returns the location and orientation of a component within a frame system. + // It returns a `PoseInFrame` describing the pose of the specified component relative to the specified destination frame. + // The `supplemental_transforms` argument can be used to augment the machine's existing frame system with additional frames. GetPose( ctx context.Context, componentName resource.Name, @@ -318,14 +336,25 @@ type Service interface { supplementalTransforms []*referenceframe.LinkInFrame, extra map[string]interface{}, ) (*referenceframe.PoseInFrame, error) + + // StopPlan stops a base component being moved by an in progress `MoveOnGlobe()` or `MoveOnMap()` call. StopPlan( ctx context.Context, req StopPlanReq, ) error + + // ListPlanStatuses returns the statuses of plans created by `MoveOnGlobe()` or `MoveOnMap()` since the motion service initialized. + // It includes plans that are in progress or have changed state in the last 24 hours. + // All repeated fields are in chronological order. ListPlanStatuses( ctx context.Context, req ListPlanStatusesReq, ) ([]PlanStatusWithID, error) + + // PlanHistory returns the plan history of the most recent `MoveOnGlobe()` or `MoveOnMap()` call by default. + // The history for earlier executions can be requested by providing an ExecutionID. + // It returns a result if the execution is active or has changed state in the last 24 hours and the machine has not reinitialized. + // Plans never change; replans always create new plans and replans share the ExecutionID of the previously executing plan. PlanHistory( ctx context.Context, req PlanHistoryReq, From 5afc94d739f875fc8d30e82b8ed47851401a04c4 Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Fri, 24 May 2024 16:05:41 -0400 Subject: [PATCH 3/9] add Move() sample attempt --- services/motion/motion.go | 59 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 59 insertions(+) diff --git a/services/motion/motion.go b/services/motion/motion.go index 21c016c9a0d..938c9e89352 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -194,6 +194,65 @@ type PlanWithStatus struct { // // // Assumes a gripper configured with name "my_gripper" on the machine // gripperName := gripper.Named("my_gripper") +// +// geometriesInFrame := []*referenceframe.GeometriesInFrame{} +// +// worldState, _ := referenceframe.NewWorldState(geometriesInFrame, nil) +// +// goalPose := referenceframe.NewPoseInFrame("my_gripper", spatialmath.NewPoseFromPoint(r3.Vector{X:-3, Y:0.5})) +// +// // Move the gripper +// moved, err := motionService.Move(context.Background(), gripperName, goalPose, worldState, nil, nil) +// +// MoveOnMap example: +// +// // Assumes a base with the name "my_base" is configured on the machine +// myBaseResourceName := base.Named("my_base") +// mySLAMServiceResourceName := slam.Named("my_slam_service") +// +// // Define a destination Pose +// myPose := spatialmath.NewPoseFromPoint(r3.Vector{Y: 10}) +// +// // Move the base component to the destination pose +// executionID, err := motionService.MoveOnMap(context.Background(), motion.MoveOnMapReq{ +// ComponentName: myBaseResourceName, +// Destination: myPose, +// SlamName: mySLAMServiceResourceName, +// }) +// +// err = motion.PollHistoryUntilSuccessOrError( +// context.Background(), +// motionService, +// time.Duration(time.Second), +// motion.PlanHistoryReq{ +// ComponentName: myBaseResourceName, +// ExecutionID: executionID, +// }, +// ) +// +// MoveOnGlobe example: +// +// // Assumes a base with the name "my_base" is configured on the machine +// // Get the resource names of the base and movement sensor +// myBaseResourceName := base.Named("myBase") +// myMvmntSensorResourceName := movementsensor.Named("my_movement_sensor") +// +// // Define a destination Point at the GPS coordinates [0, 0] +// myDestination := geo.NewPoint(0, 0) +// +// // Move the base component to the designated geographic location, as reported by the movement sensor +// executionID, err := motionService.MoveOnGlobe(context.Background(), motion.MoveOnGlobeReq{ +// ComponentName: myBaseResourceName, +// Destination: myDestination, +// MovementSensorName: myMvmntSensorResourceName, +// }) +// +// log.Printf("Move execution ID: %v", executionID) +// +// GetPose example: +// +// // Assumes a gripper configured with name "my_gripper" on the machine +// gripperName := gripper.Named("my_gripper") // myFrame := "my_gripper_offset" // // goalPose := referenceframe.PoseInFrame(0, 0, 300, 0, 0, 1, 0) From 26a041ea8310021fab73f7b885e6ec5a42cfa169 Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Fri, 24 May 2024 16:33:29 -0400 Subject: [PATCH 4/9] integrate feedback --- services/motion/motion.go | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index 938c9e89352..7d024ceee87 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -220,6 +220,7 @@ type PlanWithStatus struct { // SlamName: mySLAMServiceResourceName, // }) // +// // MoveOnMap is a non-blocking method and this line can optionally be added to block until the movement is done // err = motion.PollHistoryUntilSuccessOrError( // context.Background(), // motionService, @@ -247,7 +248,16 @@ type PlanWithStatus struct { // MovementSensorName: myMvmntSensorResourceName, // }) // -// log.Printf("Move execution ID: %v", executionID) +// // MoveOnGlobe is a non-blocking method and this line can optionally be added to block until the movement is done +// err = motion.PollHistoryUntilSuccessOrError( +// context.Background(), +// motionService, +// time.Duration(time.Second), +// motion.PlanHistoryReq{ +// ComponentName: myBaseResourceName, +// ExecutionID: executionID, +// }, +// ) // // GetPose example: // @@ -288,6 +298,7 @@ type PlanWithStatus struct { // // // Get the resource.Names of the base and of the SLAM service // myBaseResourceName := base.Named("myBase") +<<<<<<< HEAD // mySLAMServiceResourceName := slam.Named("my_slam_service") // // Define a destination Pose with respect to the origin of the map from the SLAM service "my_slam_service" // myPose := spatialmath.NewPoseFromPoint(r3.Vector{Y: 10}) @@ -316,6 +327,9 @@ type PlanWithStatus struct { // Destination: myDestination, // MovementSensorName: myMvmntSensorResourceName, // }) +======= +// // Assumes there is an active MoveOnMap or MoveOnGlobe in progress for the configured base component +>>>>>>> d52c268ed (integrate feedback) // // StopPlan example: // From 05ada06faeebe9bf9f9a39797217ffccdebc06dc Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Mon, 24 Jun 2024 10:35:46 -0700 Subject: [PATCH 5/9] add geometries to worldstate from arm/gripper tutorial --- services/motion/motion.go | 35 +++++++++++++++++------------------ 1 file changed, 17 insertions(+), 18 deletions(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index 7d024ceee87..88719c22844 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -195,9 +195,21 @@ type PlanWithStatus struct { // // Assumes a gripper configured with name "my_gripper" on the machine // gripperName := gripper.Named("my_gripper") // -// geometriesInFrame := []*referenceframe.GeometriesInFrame{} +// // Add a table obstacle to a WorldState +// obstacles := []spatialmath.Geometry{ +// spatialmath.NewBox( +// spatialmath.NewPose(r3.Vector{X: 0.0, Y: 0.0, Z: -19.0}, &spatialmath.OrientationVectorDegrees{0X: 0.0, 0Y: 0.0, 0Z: 1.0, Theta: 0.0}), +// r3.Vector{X: 2000.0, Y: 2000.0, Z: 38.0}, +// "table", +// ), +// } // -// worldState, _ := referenceframe.NewWorldState(geometriesInFrame, nil) +// // Create WorldState with included geometries +// worldState := &referenceframe.WorldState{ +// Obstacles: []*referenceframe.GeometriesInFrame{ +// referenceframe.NewGeometriesInFrame(referenceframe.World, obstacles), +// }, +// } // // goalPose := referenceframe.NewPoseInFrame("my_gripper", spatialmath.NewPoseFromPoint(r3.Vector{X:-3, Y:0.5})) // @@ -233,21 +245,11 @@ type PlanWithStatus struct { // // MoveOnGlobe example: // -// // Assumes a base with the name "my_base" is configured on the machine +// // Assumes a base with the name "myBase" is configured on the machine // // Get the resource names of the base and movement sensor // myBaseResourceName := base.Named("myBase") -// myMvmntSensorResourceName := movementsensor.Named("my_movement_sensor") -// -// // Define a destination Point at the GPS coordinates [0, 0] -// myDestination := geo.NewPoint(0, 0) -// -// // Move the base component to the designated geographic location, as reported by the movement sensor -// executionID, err := motionService.MoveOnGlobe(context.Background(), motion.MoveOnGlobeReq{ -// ComponentName: myBaseResourceName, -// Destination: myDestination, -// MovementSensorName: myMvmntSensorResourceName, -// }) // +// // Assumes there is an active MoveOnMap() or MoveonGlobe() in progress for myBase // // MoveOnGlobe is a non-blocking method and this line can optionally be added to block until the movement is done // err = motion.PollHistoryUntilSuccessOrError( // context.Background(), @@ -298,7 +300,6 @@ type PlanWithStatus struct { // // // Get the resource.Names of the base and of the SLAM service // myBaseResourceName := base.Named("myBase") -<<<<<<< HEAD // mySLAMServiceResourceName := slam.Named("my_slam_service") // // Define a destination Pose with respect to the origin of the map from the SLAM service "my_slam_service" // myPose := spatialmath.NewPoseFromPoint(r3.Vector{Y: 10}) @@ -327,9 +328,7 @@ type PlanWithStatus struct { // Destination: myDestination, // MovementSensorName: myMvmntSensorResourceName, // }) -======= -// // Assumes there is an active MoveOnMap or MoveOnGlobe in progress for the configured base component ->>>>>>> d52c268ed (integrate feedback) +// fmt.Printf("Position:", myArmMotionPose.Pose().Point(), "Orientation:", myArmMotionPose.Pose().Orientation()) // // StopPlan example: // From 16dc011f27275f4861381f7c42baa111f403dbed Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Mon, 24 Jun 2024 10:36:25 -0700 Subject: [PATCH 6/9] add motion service code snippets --- services/motion/motion.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index 88719c22844..2fd6313f41c 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -204,7 +204,7 @@ type PlanWithStatus struct { // ), // } // -// // Create WorldState with included geometries +// // Create a WorldState that has geometries included // worldState := &referenceframe.WorldState{ // Obstacles: []*referenceframe.GeometriesInFrame{ // referenceframe.NewGeometriesInFrame(referenceframe.World, obstacles), From e104461160cc4d9adb2dff73965ac9f484858b92 Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Wed, 3 Jul 2024 08:12:52 -0700 Subject: [PATCH 7/9] fix bugs in old Move() sample --- services/motion/motion.go | 34 +++++++++++++++++----------------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index 2fd6313f41c..26e71369018 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -195,26 +195,26 @@ type PlanWithStatus struct { // // Assumes a gripper configured with name "my_gripper" on the machine // gripperName := gripper.Named("my_gripper") // -// // Add a table obstacle to a WorldState -// obstacles := []spatialmath.Geometry{ -// spatialmath.NewBox( -// spatialmath.NewPose(r3.Vector{X: 0.0, Y: 0.0, Z: -19.0}, &spatialmath.OrientationVectorDegrees{0X: 0.0, 0Y: 0.0, 0Z: 1.0, Theta: 0.0}), -// r3.Vector{X: 2000.0, Y: 2000.0, Z: 38.0}, -// "table", -// ), -// } +// // Define destination +// destination := referenceframe.NewPoseInFrame("world", spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.0})) // 10 cm in X direction // -// // Create a WorldState that has geometries included -// worldState := &referenceframe.WorldState{ -// Obstacles: []*referenceframe.GeometriesInFrame{ -// referenceframe.NewGeometriesInFrame(referenceframe.World, obstacles), -// }, -// } +// // Create obstacles +// boxPose := spatialmath.NewPoseFromPoint(r3.Vector{X: 0.0, Y: 0.0, Z: 0.0}) +// boxDims := r3.Vector{X: 0.2, Y: 0.2, Z: 0.2} // 20cm x 20cm x 20cm box +// obstacle, _ := spatialmath.NewBox(boxPose, boxDims, "obstacle_1") // -// goalPose := referenceframe.NewPoseInFrame("my_gripper", spatialmath.NewPoseFromPoint(r3.Vector{X:-3, Y:0.5})) +// geometryInFrame := referenceframe.NewGeometriesInFrame("base", []spatialmath.Geometry{obstacle}) +// obstacles := []*referenceframe.GeometriesInFrame{geometryInFrame} // -// // Move the gripper -// moved, err := motionService.Move(context.Background(), gripperName, goalPose, worldState, nil, nil) +// // Create transforms +// transform := referenceframe.NewLinkInFrame("gripper", spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.1}), "transform_1", nil) +// transforms := []*referenceframe.LinkInFrame{transform} +// +// // Create a WorldState +// worldState, err := referenceframe.NewWorldState(obstacles, transforms) +// +// // Move gripper component +// moved, err := motionService.Move(context.Background(), gripperName, destination, worldState, nil, nil) // // MoveOnMap example: // From cb706ba7f4eb881ac87ddbc94e4f7be80971032f Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Wed, 3 Jul 2024 13:53:27 -0700 Subject: [PATCH 8/9] merge new changes --- services/motion/motion.go | 104 ++++++++++++-------------------------- 1 file changed, 32 insertions(+), 72 deletions(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index 26e71369018..fda98b70738 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -196,7 +196,7 @@ type PlanWithStatus struct { // gripperName := gripper.Named("my_gripper") // // // Define destination -// destination := referenceframe.NewPoseInFrame("world", spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.0})) // 10 cm in X direction +// destination := referenceframe.NewPoseInFrame("world", spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.0})) // // // Create obstacles // boxPose := spatialmath.NewPoseFromPoint(r3.Vector{X: 0.0, Y: 0.0, Z: 0.0}) @@ -207,10 +207,12 @@ type PlanWithStatus struct { // obstacles := []*referenceframe.GeometriesInFrame{geometryInFrame} // // // Create transforms -// transform := referenceframe.NewLinkInFrame("gripper", spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.1}), "transform_1", nil) +// transform := referenceframe.NewLinkInFrame("gripper", +// spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.1}), "transform_1", nil +// ) // transforms := []*referenceframe.LinkInFrame{transform} // -// // Create a WorldState +// // Create WorldState // worldState, err := referenceframe.NewWorldState(obstacles, transforms) // // // Move gripper component @@ -248,6 +250,17 @@ type PlanWithStatus struct { // // Assumes a base with the name "myBase" is configured on the machine // // Get the resource names of the base and movement sensor // myBaseResourceName := base.Named("myBase") +// myMvmntSensorResourceName := movementsensor.Named("my_movement_sensor") +// +// // Define a destination Point at the GPS coordinates [0, 0] +// myDestination := geo.NewPoint(0, 0) +// +// // Move the base component to the designated geographic location, as reported by the movement sensor +// executionID, err := motionService.MoveOnGlobe(context.Background(), motion.MoveOnGlobeReq{ +// ComponentName: myBaseResourceName, +// Destination: myDestination, +// MovementSensorName: myMvmntSensorResourceName, +// }) // // // Assumes there is an active MoveOnMap() or MoveonGlobe() in progress for myBase // // MoveOnGlobe is a non-blocking method and this line can optionally be added to block until the movement is done @@ -263,26 +276,14 @@ type PlanWithStatus struct { // // GetPose example: // -// // Assumes a gripper configured with name "my_gripper" on the machine -// gripperName := gripper.Named("my_gripper") -// myFrame := "my_gripper_offset" -// -// goalPose := referenceframe.PoseInFrame(0, 0, 300, 0, 0, 1, 0) -// -// // Move the gripper -// moved, err := motionService.Move(context.Background(), gripperName, goalPose, worldState, nil, nil) -// -// GetPose example: -// // // Insert code to connect to your machine. // // (see CONNECT tab of your machine's page in the Viam app) // // // Assumes a gripper configured with name "my_gripper" on the machine // gripperName := gripper.Named("my_gripper") -// myFrame := "my_gripper_offset" // // // Access the motion service -// motionService, err := motion.FromRobot(robot, "builtin") +// motionService, err := motion.FromRobot(machine, "builtin") // if err != nil { // logger.Fatal(err) // } @@ -294,77 +295,36 @@ type PlanWithStatus struct { // logger.Info("Position of myArm from the motion service:", myArmMotionPose.Pose().Point()) // logger.Info("Orientation of myArm from the motion service:", myArmMotionPose.Pose().Orientation()) // -// MoveOnMap example: -// -// motionService, err := motion.FromRobot(robot, "builtin") +// StopPlan example: // -// // Get the resource.Names of the base and of the SLAM service +// motionService, err := motion.FromRobot(machine, "builtin") // myBaseResourceName := base.Named("myBase") -// mySLAMServiceResourceName := slam.Named("my_slam_service") -// // Define a destination Pose with respect to the origin of the map from the SLAM service "my_slam_service" -// myPose := spatialmath.NewPoseFromPoint(r3.Vector{Y: 10}) -// -// // Move the base component to the destination pose of Y=10, a location of (0, 10, 0) in respect to the origin of the map -// executionID, err := motionService.MoveOnMap(context.Background(), motion.MoveOnMapReq{ -// ComponentName: myBaseResourceName, -// Destination: myPose, -// SlamName: mySLAMServiceResourceName, -// }) -// -// MoveOnGlobe example: // -// motionService, err := motion.FromRobot(robot, "builtin") -// -// // Get the resource.Names of the base and movement sensor -// myBaseResourceName := base.Named("myBase") // myMvmntSensorResourceName := movement_sensor.Named("my_movement_sensor") -// // Define a destination Point at the GPS coordinates [0, 0] // myDestination := geo.NewPoint(0, 0) // -// // Move the base component to the designated geographic location, as reported by the movement sensor -// ctx := context.Background() -// executionID, err := motionService.MoveOnGlobe(ctx, motion.MoveOnGlobeReq{ -// ComponentName: myBaseResourceName, -// Destination: myDestination, -// MovementSensorName: myMvmntSensorResourceName, -// }) -// fmt.Printf("Position:", myArmMotionPose.Pose().Point(), "Orientation:", myArmMotionPose.Pose().Orientation()) -// -// StopPlan example: -// -// motionService, err := motion.FromRobot(robot, "builtin") -// myBaseResourceName := base.Named("myBase") -// ctx := context.Background() -// -// // Assuming a move_on_globe started the execution -// // myMvmntSensorResourceName := movement_sensor.Named("my_movement_sensor") -// // myDestination := geo.NewPoint(0, 0) -// // executionID, err := motionService.MoveOnGlobe(ctx, motion.MoveOnGlobeReq{ -// // ComponentName: myBaseResourceName, -// // Destination: myDestination, -// // MovementSensorName: myMvmntSensorResourceName, -// // }) -// +// // Assuming a `MoveOnGlobe()`` started the execution // // Stop the base component which was instructed to move by `MoveOnGlobe()` or `MoveOnMap()` // err := motionService.StopPlan(context.Background(), motion.StopPlanReq{ // ComponentName: s.req.ComponentName, // }) // -// GetPlan example: +// ListPlanStatuses example: +// +// motionService, err := motion.FromRobot(machine, "builtin") // -// motionService, err := motion.FromRobot(robot, "builtin") // // Get the plan(s) of the base component's most recent execution i.e. `MoveOnGlobe()` or `MoveOnMap()` call. -// ctx := context.Background() -// planHistory, err := motionService.PlanHistory(ctx, motion.PlanHistoryReq{ -// ComponentName: s.req.ComponentName, -// }) +// planStatuses, err := motionService.ListPlanStatuses(context.Background(), motion.ListPlanStatusesReq{}) // -// ListPlanStatus example: +// PlanHistory example: // -// motionService, err := motion.FromRobot(robot, "builtin") -// // Get the plan(s) of the base component's most recent execution i.e. `MoveOnGlobe()` or `MoveOnMap()` call. -// ctx := context.Background() -// planStatuses, err := motionService.ListPlanStatuses(ctx, motion.ListPlanStatusesReq{}) +// // Get the resource name of the base component +// myBaseResourceName := base.Named("myBase") +// +// // Get the plan history of the base component's most recent execution (e.g., MoveOnGlobe or MoveOnMap call) +// planHistory, err := motionService.PlanHistory(context.Background(), motion.PlanHistoryReq{ +// ComponentName: myBaseResourceName, +// }) type Service interface { resource.Resource From 3649a1bca57a344a0c7040d5f2081495bd27fbf7 Mon Sep 17 00:00:00 2001 From: sky leilani <45158875+skyleilani@users.noreply.github.com> Date: Wed, 3 Jul 2024 14:10:46 -0700 Subject: [PATCH 9/9] try to fix test --- services/motion/motion.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/services/motion/motion.go b/services/motion/motion.go index fda98b70738..db9c5707196 100644 --- a/services/motion/motion.go +++ b/services/motion/motion.go @@ -195,7 +195,7 @@ type PlanWithStatus struct { // // Assumes a gripper configured with name "my_gripper" on the machine // gripperName := gripper.Named("my_gripper") // -// // Define destination +// // Define a destination Pose // destination := referenceframe.NewPoseInFrame("world", spatialmath.NewPoseFromPoint(r3.Vector{X: 0.1, Y: 0.0, Z: 0.0})) // // // Create obstacles