Motion Service

The motion service enables your machine to plan and move itself or its components relative to itself, other machines, and the world. The motion service:

  1. Gathers the current positions of the machine’s components as defined with the frame system.
  2. Plans the necessary motions to move a component to a given destination while obeying any constraints you configure.

The motion service can:

  • use motion planning algorithms locally on your machine to plan coordinated motion across many components.
  • pass movement requests through to individual components which have implemented their own motion planning.

Used with

* Required for use

Configuration

You need to configure frames for your machine’s components with the frame system. This defines the spatial context within which the motion service operates.

The motion service itself is enabled on the machine by default, so you do not need to do any extra configuration in the Viam app to enable it.

API

The motion service supports the following methods:

Method NameDescription
MoveMove multiple components in a coordinated way to achieve a desired motion.
GetPoseGet the current location and orientation of a component as a Pose.
MoveOnMapMove a base component to a Pose in respect to the origin of a SLAM map. Use the machine’s position reported by the SLAM service to check the location of the machine.
MoveOnGlobeMove a base component to a destination GPS point. Use a Movement Sensor to measure the machine’s GPS coordinates.
StopPlanStop a base component being moved by an in progress MoveOnGlobe or MoveOnMap call.
GetPlanReturns the plan history of the most recent MoveOnGlobe or MoveOnMap call to move a base component.
ListPlanStatusesReturns the plan statuses created by MoveOnGlobe or MoveOnMap calls.
DoCommandSend arbitrary commands to the resource.
CloseSafely shut down the resource and prevent further use.

Move

The Move method is the primary way to move multiple components, or to move any object to any other location. Given a destination pose and a component to move to that destination, Move will:

  1. Construct a full kinematic chain from goal to destination including all movable components in between.
  2. Solve that chain to move the specified component frame to the destination while adhering to any constraints.
  3. Execute that movement to move the actual machine.
  4. Return whether or not this process succeeded.

The motion service takes the volumes associated with all configured machine components (local and remote) into account for each request to ensure that the machine does not collide with itself or other known objects.

Parameters:

  • component_name (ResourceName): The ResourceName of the piece of the robot that should arrive at the destination. Note that move moves the distal end of the component to the destination. For example, when moving a robotic arm, the piece that will arrive at the destination is the end effector attachment point, not the base of the arm.

  • destination (PoseInFrame): Describes where the component_name frame should be moved to. Can be any pose, from the perspective of any component whose location is configured as a frame.

    Note that the destination pose is relative to the distal end of the specified frame. This means that if the destination is the same as the component_name frame, for example an arm’s frame, then a pose of {X: 10, Y: 0, Z: 0} will move that arm’s end effector by 10 mm in the local X direction.

  • world_state (WorldState) (optional): Data structure specifying information about the world around the machine. Used to augment the motion solving process. world_state includes obstacles and transforms:

    • Obstacles: Geometries located at a pose relative to some frame. When solving a motion plan with movable frames that contain inherent geometries, the solved path is constrained such that none of those inherent geometries intersect with the obstacles. Important considerations:
      • If a motion begins with a component already in collision with an obstacle, collisions between that specific component and that obstacle will not be checked.
      • The motion service assumes that obstacles are static. If a worldstate obstacle is physically attached to a part of the robot such that it will move with the robot, specify it with transforms.
      • Obstacles are defined by a pose and a geometry with dimensions. The pose location is the point at the center of the geometry.
      • Obstacle locations are defined with respect to the origin of the specified frame. Their poses are relative to the origin of the specified frame. An obstacle associated with the frame of an arm with a pose of {X: 0, Y: 0, Z: -10} is interpreted as being 10mm below the base of the arm, not 10mm below the end effector. This is different from destination and component_name, where poses are relative to the distal end of a frame.
    • Transforms: A list of PoseInFrame messages that specify other transformations to temporarily add to the frame system at solve time. Transforms can be used to account for geometries that are attached to the robot but not configured as robot components. For example, you could use a transform to represent the volume of a marker held in your machine’s gripper. Transforms are not added to the config or carried into later processes.
  • constraints (Constraints) (optional): Pass in motion constraints. By default, motion is unconstrained with the exception of obstacle avoidance.

  • extra (Mapping[str, Any]) (optional): A generic struct, containing extra options to pass to the underlying RPC call.

Returns:

  • (bool): Whether the move was successful.

For more information, see the Python SDK Docs.

motion = MotionClient.from_robot(robot=robot, name="builtin")

# Assumes a gripper configured with name "my_gripper" on the machine
gripper_name = Gripper.get_resource_name("my_gripper")
my_frame = "my_gripper_offset"

goal_pose = Pose(x=0, y=0, z=300, o_x=0, o_y=0, o_z=1, theta=0)

# Move the gripper
moved = await motion.move(component_name=gripper_name,
                          destination=PoseInFrame(reference_frame="myFrame",
                                                  pose=goal_pose),
                          world_state=worldState,
                          constraints={},
                          extra={})

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.

  • componentName (resource.Name): The resource.Name of the piece of the robot that should arrive at the destination. Note that Move moves the distal end of the component to the destination. For example, when moving a robotic arm, the piece that will arrive at the destination is the end effector attachment point, not the base of the arm.

  • destination (PoseInFrame): Describes where the component_name should end up. Can be any pose, from the perspective of any component whose location is configured as a frame.

    Note that the destination pose is relative to the distal end of the specified frame. This means that if the destination is the same as the component_name frame, for example an arm’s frame, then a pose of {X: 10, Y: 0, Z: 0} will move that arm’s end effector by 10 mm in the local X direction.

  • worldState (WorldState): Data structure specifying information about the world around the machine. Used to augment the motion solving process. worldState includes obstacles and transforms:

    • Obstacles: Geometries located at a pose relative to some frame. When solving a motion plan with movable frames that contain inherent geometries, the solved path is constrained such that none of those inherent geometries intersect with the obstacles. Important considerations:
      • If a motion begins with a component already in collision with an obstacle, collisions between that specific component and that obstacle will not be checked.
      • The motion service assumes that obstacles are static. If a worldstate obstacle is physically attached to a part of the robot such that it will move with the robot, specify it with transforms.
      • Obstacles are defined by a (pose) and a (geometry) with dimensions. The pose location is the point at the center of the geometry.
      • Obstacle locations are defined with respect to the origin of the specified frame. Their poses are relative to the origin of the specified frame. An obstacle associated with the frame of an arm with a pose of {X: 0, Y: 0, Z: -10} is interpreted as being 10mm below the base of the arm, not 10mm below the end effector. This is different from destination and componentName, where poses are relative to the distal end of a frame.
    • Transforms: A list of PoseInFrame messages that specify other transformations to temporarily add to the frame system at solve time. Transforms can be used to account for geometries that are attached to the robot but not configured as robot components. For example, you could use a transform to represent the volume of a marker held in your machine’s gripper. Transforms are not added to the config or carried into later processes.
  • constraints (Constraints): Pass in optional motion constraints. By default, motion is unconstrained with the exception of obstacle avoidance.

  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • (bool): Whether the move was successful.
  • (error): An error, if one occurred.

For more information, see the Go SDK Docs.

motionService, err := motion.FromRobot(robot, "builtin")

// 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

GetPose gets the location and orientation of a component within the frame system. The return type of this function is a PoseInFrame describing the pose of the specified component with respect to the specified destination frame. You can use the supplemental_transforms argument to augment the machine’s existing frame system with supplemental frames.

Parameters:

  • component_name (ResourceName): The ResourceName of the piece of the machine whose pose is returned.

  • destination_frame (str): The name of the frame with respect to which the component’s pose is reported.

  • supplemental_transforms (Optional[List[Transforms]]) (optional): A list of Transform objects. A Transform represents an additional frame which is added to the machine’s frame system. It consists of the following fields:

    • pose_in_observer_frame: Provides the relationship between the frame being added and another frame.
    • physical_object: An optional Geometry can be added to the frame being added.
    • reference_frame: Specifies the name of the frame which will be added to the frame system.

    When supplemental_transforms are provided, a frame system is created within the context of the GetPose function. This new frame system builds off the machine’s frame system and incorporates the Transforms provided. If the result of adding the Transforms results in a disconnected frame system, an error is thrown.

  • extra (Mapping[str, Any]) (optional): A generic struct, containing extra options to pass to the underlying RPC call.

Returns:

For more information, see the Python SDK Docs.

The following code example gets the pose of the tip of a gripper named my_gripper which is attached to the end of an arm, in the “world” reference_frame:

from viam.components.gripper import Gripper
from viam.services.motion import MotionClient

# Assume that the connect function is written and will return a valid machine.
robot = await connect()

motion = MotionClient.from_robot(robot=robot, name="builtin")
gripperName = Gripper.get_resource_name("my_gripper")
gripperPoseInWorld = await motion.get_pose(component_name=gripperName,
                                           destination_frame="world")

For a more complicated example, take the same scenario and get the pose of the same gripper with respect to an object situated at a location (100, 200, 0) relative to the “world” frame:

from viam.components.gripper import Gripper
from viam.services.motion import MotionClient
from viam.proto.common import Transform, PoseInFrame, Pose

# Assume that the connect function is written and will return a valid machine.
robot = await connect()

motion = MotionClient.from_robot(robot=robot, name="builtin")
objectPose = Pose(x=100, y=200, z=0, o_x=0, o_y=0, o_z=1, theta=0)
objectPoseInFrame = PoseInFrame(reference_frame="world", pose=objectPose)
objectTransform = Transform(reference_frame="object",
                            pose_in_observer_frame=objectPoseInFrame)
gripperName = Gripper.get_resource_name("my_gripper")
gripperPoseInObjectFrame = await motion.get_pose(
  component_name=gripperName,
  destination_frame="world",
  supplemental_transforms=objectTransform
)

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.

  • componentName (resource.Name): The resource.Name of the piece of the machine whose pose is returned.

  • destinationFrame (string): The name of the frame with respect to which the component’s pose is reported.

  • supplementalTransforms (LinkInFrame): An optional list of LinkInFrames. A LinkInFrame represents an additional frame which is added to the machine’s frame system. It consists of:

    • a PoseInFrame: Provides the relationship between the frame being added and another frame.
    • Geometry: An optional Geometry can be added to the frame being added. When supplementalTransforms are provided, a frame system is created within the context of the GetPose function. This new frame system builds off the machine’s frame system and incorporates the LinkInFrames provided. If the result of adding the LinkInFrames results in a disconnected frame system, an error is thrown.
  • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

For more information, see the Go SDK Docs.

// 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")
if err != nil {
  logger.Fatal(err)
}

myArmMotionPose, err := motionService.GetPose(context.Background(), my_gripper, referenceframe.World, nil, nil)
if err != nil {
  logger.Fatal(err)
}
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

Move a base component to a destination Pose on a SLAM map.

MoveOnMap() is non blocking, meaning the motion service will move the component to the destination Pose after MoveOnMap() returns.

Each successful MoveOnMap() call returns a unique ExecutionID which you can use to identify all plans generated during the MoveOnMap() call.

You can monitor the progress of the MoveOnMap() call by querying GetPlan() and ListPlanStatuses().

Use the machine’s position reported by the SLAM service to check the location of the machine.

MoveOnMap() is intended for use with the navigation service, providing autonomous indoor navigation for rover bases.

Parameters:

  • component_name (ResourceName): The ResourceName of the base to move.
  • destination (Pose): The destination, which can be any Pose with respect to the SLAM map’s origin.
  • slam_service_name (ResourceName): The ResourceName of the SLAM service from which the SLAM map is requested.
  • configuration (Optional[MotionConfiguration]): The configuration you want to set across this machine for this motion service. This parameter and each of its fields are optional.
    • obstacle_detectors (Iterable[ObstacleDetector]): The names of each vision service and camera resource pair you want to use for transient obstacle avoidance.
    • position_polling_frequency_hz (float): The frequency in hz to poll the position of the machine.
    • obstacle_polling_frequency_hz (float): The frequency in hz to poll the vision service for new obstacles.
    • plan_deviation_m (float): The distance in meters that the machine can deviate from the motion plan. By default this is set to 2.6 m which is an appropriate value for outdoor usage. When you use the MoveOnMap() method from the CONTROL tab, the default is overwritten to 0.5 m for testing.
    • linear_m_per_sec (float): Linear velocity this machine should target when moving.
    • angular_degs_per_sec (float): Angular velocity this machine should target when turning.
  • obstacles Optional[Iterable[Geometry]]: Obstacles, specified in the SLAM frame coordinate system, to be considered when planning the motion of the component.
  • extra (Optional[Dict[str, Any]]): Extra options to pass to the underlying RPC call.
  • timeout (Optional[float]): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (str): ExecutionID of the MoveOnMap call.

For more information, see the Python SDK Docs.

motion = MotionClient.from_robot(robot=robot, name="builtin")

# Get the ResourceNames of the base and SLAM service
my_base_resource_name = Base.get_resource_name("my_base")
my_slam_service_name = SLAMClient.get_resource_name("my_slam_service")

# Define a destination pose with respect to the origin of the map from the SLAM
# service "my_slam_service"
my_pose = Pose(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
execution_id = await motion.move_on_map(component_name=my_base_resource_name,
                                        destination=my_pose,
                                        slam_service_name=my_slam_service_name)

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • req MoveOnMapReq: A MoveOnMapReq which contains the following values:
    • ComponentName (resource.Name): The resource.Name of the base to move.
    • Destination (spatialmath.Pose): The destination, which can be any Pose with respect to the SLAM map’s origin.
    • SlamName (resource.Name): The resource.Name of the SLAM service from which the SLAM map is requested.
    • MotionConfig (*MotionConfiguration): The configuration you want to set across this machine for this motion service. This parameter and each of its fields are optional.
      • ObstacleDetectors ([]ObstacleDetectorName): The names of each vision service and camera resource pair you want to use for transient obstacle avoidance.
      • PositionPollingFreqHz (float64): The frequency in hz to poll the position of the machine.
      • ObstaclePollingFreqHz (float64): The frequency in hz to poll the vision service for new obstacles.
      • PlanDeviationM (float64): The distance in meters that the machine can deviate from the motion plan. By default this is set to 2.6 m which is an appropriate value for outdoor usage. When you use the the CONTROL tab, the underlying calls to MoveOnMap() use 0.5 m instead.
      • LinearMPerSec (float64): Linear velocity this machine should target when moving.
      • AngularDegsPerSec (float64): Angular velocity this machine should target when turning.
    • Obstacles ([]spatialmath.Geometry): Obstacles, specified in the SLAM frame coordinate system, to be considered when planning the motion of the component.
    • Extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

For more information, see the Go SDK Docs.

motionService, err := motion.FromRobot(robot, "builtin")

// Get the resource.Names of the base and of the SLAM service
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

Move a base component to a destination GPS point, represented in geographic notation (latitude, longitude). Use a movement sensor to check the location of the machine.

MoveOnGlobe() is non blocking, meaning the motion service will move the component to the destination GPS point after MoveOnGlobe() returns.

Each successful MoveOnGlobe() call returns a unique ExecutionID which you can use to identify all plans generated during the MoveOnGlobe().

You can monitor the progress of the MoveOnGlobe() call by querying GetPlan() and ListPlanStatuses().

MoveOnGlobe() is intended for use with the navigation service, providing autonomous GPS navigation for rover bases.

Parameters:

  • component_name (ResourceName): The ResourceName of the base to move.
  • destination (GeoPoint): The location of the component’s destination, represented in geographic notation as a GeoPoint (lat, lng).
  • movement_sensor_name (ResourceName): The ResourceName of the movement sensor that you want to use to check the machine’s location.
  • obstacles (Optional[Sequence[GeoObstacle]]): Obstacles to consider when planning the motion of the component, with each represented as a GeoObstacle.
    • Default: None
  • heading (Optional[float]): The compass heading, in degrees, that the machine’s movement sensor should report at the destination point.
    • Range: [0-360) 0: North, 90: East, 180: South, 270: West
    • Default: None
  • configuration (Optional[MotionConfiguration]): The configuration you want to set across this machine for this motion service. This parameter and each of its fields are optional.
    • obstacle_detectors (Iterable[ObstacleDetector]): The names of each vision service and camera resource pair you want to use for transient obstacle avoidance.
    • position_polling_frequency_hz (float): The frequency in hz to poll the position of the machine.
    • obstacle_polling_frequency_hz (float): The frequency in hz to poll the vision service for new obstacles.
    • plan_deviation_m (float): The distance in meters that the machine can deviate from the motion plan.
    • linear_m_per_sec (float): Linear velocity this machine should target when moving.
    • angular_degs_per_sec (float): Angular velocity this machine should target when turning.
  • extra (Optional[Dict[str, Any]]): Extra options to pass to the underlying RPC call.
  • timeout (Optional[float]): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

  • (str): ExecutionID of the MoveOnGlobe call.

For more information, see the Python SDK Docs.

motion = MotionClient.from_robot(robot=robot, name="builtin")

# Get the ResourceNames of the base and movement sensor
my_base_resource_name = Base.get_resource_name("my_base")
mvmnt_sensor_resource_name = MovementSensor.get_resource_name(
    "my_movement_sensor")
#  Define a destination GeoPoint at the GPS coordinates [0, 0]
my_destination = movement_sensor.GeoPoint(latitude=0, longitude=0)

# Move the base component to the designated geographic location, as reported by
# the movement sensor
execution_id = await motion.move_on_globe(
    component_name=my_base_resource_name,
    destination=my_destination,
    movement_sensor_name=mvmnt_sensor_resource_name)

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • req MoveOnGlobeReq: A MoveOnGlobeReq which contains the following values:
    • componentName (resource.Name): The resource.Name of the base to move.
    • destination (*geo.Point): The location of the component’s destination, represented in geographic notation as a Point (lat, lng).
    • heading (float64): The compass heading, in degrees, that the machine’s movement sensor should report at the destination point.
      • Range: [0-360) 0: North, 90: East, 180: South, 270: West
      • Default: 0
    • movementSensorName (resource.Name): The resource.Name of the movement sensor that you want to use to check the machine’s location.
    • obstacles ([]*spatialmath.GeoObstacle): Obstacles to consider when planning the motion of the component, with each represented as a GeoObstacle.
      • Default: nil
    • motionConfig (*MotionConfiguration): The configuration you want to set across this machine for this motion service. This parameter and each of its fields are optional.
      • ObstacleDetectors ([]ObstacleDetectorName): The names of each vision service and camera resource pair you want to use for transient obstacle avoidance.
      • PositionPollingFreqHz (float64): The frequency in hz to poll the position of the machine.
      • ObstaclePollingFreqHz (float64): The frequency in hz to poll the vision service for new obstacles.
      • PlanDeviationM (float64): The distance in meters that the machine can deviate from the motion plan.
      • LinearMPerSec (float64): Linear velocity this machine should target when moving.
      • AngularDegsPerSec (float64): Angular velocity this machine should target when turning.
    • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

For more information, see the Go SDK Docs.

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,
})

StopPlan

Stop a base component being moved by an in progress MoveOnGlobe or MoveOnMap call.

Parameters:

  • component_name (ResourceName): The ResourceName of the base to stop.
  • extra (Optional[Dict[str, Any]]): Extra options to pass to the underlying RPC call.
  • timeout (Optional[float]): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

For more information, see the Python SDK Docs.

motion = MotionClient.from_robot(robot=robot, name="builtin")
my_base_resource_name = Base.get_resource_name("my_base")

# Assuming a move_on_globe started started the execution
# mvmnt_sensor = MovementSensor.get_resource_name("my_movement_sensor")
# my_destination = movement_sensor.GeoPoint(latitude=0, longitude=0)
# execution_id = await motion.move_on_globe(
#    component_name=my_base_resource_name,
#    destination=my_destination,
#    movement_sensor_name=mvmnt_sensor_resource_name)

# Stop the base component which was instructed to move by `MoveOnGlobe()`
# or `MoveOnMap()`
my_base_resource_name = Base.get_resource_name("my_base")
await motion.stop_plan(component_name=mvmnt_sensor)

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • req StopPlanReq: A StopPlanReq which contains the following values:

Returns:

  • (error): An error, if one occurred.

For more information, see the Go SDK Docs.

motionService, err := motion.FromRobot(robot, "builtin")
myBaseResourceName := base.Named("myBase")
ctx := context.Background()

// Assuming a move_on_globe started 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,
// })

// 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

By default, returns the plan history of the most recent MoveOnGlobe or MoveOnMap call to move a base component.

The plan history for executions before the most recent can be requested by providing an ExecutionID in the request.

Returns a result if both of the following conditions are met:

  • the execution (call to MoveOnGlobe or MoveOnMap) is still executing or changed state within the last 24 hours
  • the machine has not reinitialized

Plans never change.

Replans always create new plans.

Replans share the ExecutionID of the previously executing plan.

All repeated fields are in chronological order.

Parameters:

  • component_name (ResourceName): The ResourceName of the base to stop.
  • lastPlanOnly (Optional[bool]): If true, the response will only return the the last plan for the component. If the executionID parameter is non empty then the last plan for the component & executionID is returned.
  • executionID (Optional[str]): If non empty, the response will return the plans of the provided execution & component. Useful for retrieving plans from executions before the current execution.
  • extra (Optional[Dict[str, Any]]): Extra options to pass to the underlying RPC call.
  • timeout (Optional[float]): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

For more information, see the Python SDK Docs.

motion = MotionClient.from_robot(robot=robot, name="builtin")
my_base_resource_name = Base.get_resource_name("my_base")
# Get the plan(s) of the base component which was instructed
# to move by `MoveOnGlobe()` or `MoveOnMap()`
resp = await motion.get_plan(component_name=my_base_resource_name)

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • req PlanHistoryReq: A PlanHistoryReq which contains the following values:
    • componentName (resource.Name): The resource.Name of the base to stop.
    • lastPlanOnly (bool): If true, the response will only return the the last plan for the component / execution
    • executionID (ExecutionID): If non empty, the response will return the plans of the provided execution & component. Useful for retrieving plans from executions before the current execution.
    • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • ([]PlanWithStatus): PlanWithStatus contains a plan, its current status, and all state changes that came prior sorted by ascending timestamp.
  • (error): An error, if one occurred.

For more information, see the Go SDK Docs.

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,
})

ListPlanStatuses

Returns the statuses of plans created by MoveOnGlobe or MoveOnMap calls that meet at least one of the following conditions since the motion service initialized:

  • the plan’s status is in progress
  • the plan’s status changed state within the last 24 hours

All repeated fields are in chronological order.

Parameters:

  • onlyActivePlans (Optional[bool]): If true, the response will only return plans which are executing.
  • extra (Optional[Dict[str, Any]]): Extra options to pass to the underlying RPC call.
  • timeout (Optional[float]): An option to set how long to wait (in seconds) before calling a time-out and closing the underlying RPC call.

Returns:

For more information, see the Python SDK Docs.

motion = MotionClient.from_robot(robot=robot, name="builtin")
# List the plan statuses of the motion service within the TTL
resp = await motion.list_plan_statuses()

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.
  • req ListPlanStatusesReq: A ListPlanStatusesReq which contains the following values:
    • onlyActivePlans (bool): If true, the response will only return plans which are executing.
    • extra (map[string]interface{}): Extra options to pass to the underlying RPC call.

Returns:

  • ([]PlanStatusWithID): PlanStatusWithID describes the state of a given plan at a point in time plus the PlanId, ComponentName and ExecutionID the status is associated with.
  • (error): An error, if one occurred.

For more information, see the Go SDK Docs.

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{})

DoCommand

Execute model-specific commands that are not otherwise defined by the service API. For built-in service models, any model-specific commands available are covered with each model’s documentation. If you are implementing your own motion service and add features that have no built-in API method, you can access them with DoCommand.

Parameters:

Returns:

For more information, see the Python SDK Docs.

# Access the motion service
motion = MotionClient.from_robot(robot=robot, name="builtin")

my_command = {
  "command": "dosomething",
  "someparameter": 52
}

await motion.do_command(my_command)

Parameters:

Returns:

// Access the motion service
motionService, err := motion.FromRobot(robot, "builtin")

resp, err := motionService.DoCommand(ctx, map[string]interface{}{"command": "dosomething", "someparameter": 52})

For more information, see the Go SDK Docs.

Close

Safely shut down the resource and prevent further use.

Parameters:

  • None

Returns:

  • None
motion = MotionClient.from_robot(robot, "builtin")

await motion.close()

For more information, see the Python SDK Docs.

Parameters:

  • ctx (Context): A Context carries a deadline, a cancellation signal, and other values across API boundaries.

Returns:

  • (error) : An error, if one occurred.
motionService, err := motion.FromRobot(robot, "builtin")

err := motionService.Close(ctx)

For more information, see the Go SDK Docs.

Test the motion service

You can test motion on your machine from the CONTROL tab.

Motion card on the Control tab

Click on the Move button to issue MoveOnMap() requests.

Next steps

The following tutorials contain complete example code for interacting with a robot arm through the arm component API, and with the motion service API, respectively: