Graph Nav

For clients to the graphnav service.

class bosdyn.client.graph_nav.GraphNavClient[source]

Bases: BaseClient

Client to the GraphNav service.

default_service_name = 'graph-nav-service'
service_type = 'bosdyn.api.graph_nav.GraphNavService'
update_from(other)[source]

Adopt key objects like processors, logger, and wallet from other.

set_localization_full_response(initial_guess_localization, ko_tform_body=None, max_distance=None, max_yaw=None, fiducial_init=2, use_fiducial_id=None, refine_fiducial_result_with_icp=False, do_ambiguity_check=False, refine_with_visual_features=False, verify_visual_features_quality=False, **kwargs)[source]

Version of set_localization which returns the full response, rather than only the Localization message.

set_localization_async_full_response(initial_guess_localization, ko_tform_body=None, max_distance=None, max_yaw=None, fiducial_init=2, use_fiducial_id=None, refine_fiducial_result_with_icp=False, do_ambiguity_check=False, refine_with_visual_features=False, verify_visual_features_quality=False, **kwargs)[source]

Async version of set_localization_full_response()

set_localization(initial_guess_localization, ko_tform_body=None, max_distance=None, max_yaw=None, fiducial_init=2, use_fiducial_id=None, refine_fiducial_result_with_icp=False, do_ambiguity_check=False, refine_with_visual_features=False, verify_visual_features_quality=False, **kwargs)[source]

Trigger a manual localization. Typically done to provide the initial localization.

Parameters:
  • initial_guess_localization (nav_pb2.Localization) – Operator-supplied guess at localization.

  • ko_tform_body – Robot SE3Pose protobuf when the initial_guess was made.

  • max_distance – [optional] Margin of distance (meters) away from the initial guess.

  • max_yaw – [optional] Margin of angle (radians) away from the initial guess.

  • fiducial_init – Tells the initializer whether to use fiducials, and how to use them.

  • use_fiducial_id – If using FIDUCIAL_INIT_SPECIFIC, this is the specific fiducial ID to use for initialization.

  • refine_fiducial_result_with_icp – Boolean determining if ICP will run after a fiducial is used for an initial guess.

  • do_ambiguity_check – Boolean where if true, consider how nearby localizations appear.

  • refine_with_visual_features – Boolean determining if visual features should be used to refine the estimate. When set,

  • refine_fiducial_result_with_icp. (this value overrides) –

  • verify_visual_features_quality – When refine_with_visual_features is set, determines if an error is asserted when the

  • unsuccessful. (refinement is) –

Returns:

The resulting localization after being triggered with a guess.

Raises:
set_localization_async(initial_guess_localization, ko_tform_body=None, max_distance=None, max_yaw=None, fiducial_init=2, use_fiducial_id=None, refine_fiducial_result_with_icp=False, do_ambiguity_check=False, refine_with_visual_features=False, verify_visual_features_quality=False, **kwargs)[source]

Async version of set_localization()

get_localization_state(request_live_point_cloud=False, request_live_images=False, request_live_terrain_maps=False, request_live_world_objects=False, request_live_robot_state=False, waypoint_id=None, request_gps_state=False, **kwargs)[source]

Obtain current localization state of the robot.

Returns:

The current localization protobuf for the robot.

Raises:

RpcError – Problem communicating with the robot.

get_localization_state_async(request_live_point_cloud=False, request_live_images=False, request_live_terrain_maps=False, request_live_world_objects=False, request_live_robot_state=False, waypoint_id=None, request_gps_state=False, **kwargs)[source]

Async version of get_localization_state().

navigate_route(route, cmd_duration, route_follow_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, **kwargs)[source]

Navigate the given route.

Parameters:
  • route – Route protobuf of the route to follow.

  • route_follow_params – What should the robot do if it is not at the expected point in the

  • route

  • blocked. (or the route is) –

  • travel_params – API TravelParams for the route.

  • cmd_duration – Number of seconds the command can run for.

  • leases – Leases to show ownership of necessary resources. Will use the client’s leases by default.

  • timesync_endpoint – Use this endpoint for timesync fields. Will use the client’s endpoint by default.

  • command_id – If not None, this continues an existing navigate_route command with the given ID. If None,

  • used. (a new command_id will be) –

  • destination_waypoint_tform_body_goal – SE2Pose protobuf of an offset relative to the destination waypoint.

  • kwargs – Passed to underlying RPC. Example: timeout=5 to cancel the RPC after 5 seconds.

Returns:

Command ID to use in feedback lookup.

Raises:
navigate_route_async(route, cmd_duration, route_follow_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, **kwargs)[source]

Async version of navigate_route()

navigate_route_full(route, route_follow_params, cmd_duration, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, **kwargs)[source]

Identical to navigate_route(), except will return the full NavigateRouteResponse.

navigate_route_full_async(route, cmd_duration, route_follow_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, **kwargs)[source]

Async version of navigate_route_full().

navigate_to(destination_waypoint_id, cmd_duration, route_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, route_blocked_behavior=None, **kwargs)[source]

Navigate to a specific waypoint along a route chosen by the GraphNav service.

Parameters:
  • destination_waypoint_id – Waypoint id string for where to go to.

  • cmd_duration – Number of seconds the command can run for.

  • route_params – API RouteGenParams for the route.

  • travel_params – API TravelParams for the route.

  • leases – Leases to show ownership of necessary resources. Will use the client’s leases by default.

  • timesync_endpoint – Use this endpoint for timesync fields. Will use the client’s endpoint by default.

  • command_id – If not None, this continues an existing navigate_to command with the given ID. If None,

  • used. (a new command_id will be) –

  • destination_waypoint_tform_body_goal – SE2Pose protobuf of an offset relative to the destination waypoint.

  • route_blocked_behavior – Defines robot behavior when route is block. If None robot will reroute.

Returns:

Command ID to use in feedback lookup.

Return type:

int

Raises:
navigate_to_async(destination_waypoint_id, cmd_duration, route_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, route_blocked_behavior=None, **kwargs)[source]

Async version of navigate_to().

navigate_to_full(destination_waypoint_id, cmd_duration, route_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, route_blocked_behavior=None, **kwargs)[source]

Identical to navigate_to(), except will return the full NavigateToResponse.

navigate_to_full_async(destination_waypoint_id, cmd_duration, route_params=None, travel_params=None, leases=None, timesync_endpoint=None, command_id=None, destination_waypoint_tform_body_goal=None, route_blocked_behavior=None, **kwargs)[source]

Async version of navigate_to_full().

navigate_to_anchor(seed_tform_goal, cmd_duration, route_params=None, travel_params=None, leases=None, timesync_endpoint=None, goal_waypoint_rt_seed_ewrt_seed_tolerance=None, command_id=None, gps_navigation_params=None, **kwargs)[source]

Navigate to a pose in seed frame along a route chosen by the GraphNav service.

Parameters:
  • seed_tform_goal – SE3Pose protobuf of the goal pose in seed frame.

  • cmd_duration – Number of seconds the command can run for.

  • route_params – API RouteGenParams for the route.

  • travel_params – API TravelParams for the route.

  • leases – Leases to show ownership of necessary resources. Will use the client’s leases by default.

  • timesync_endpoint – Use this endpoint for timesync fields. Will use the client’s endpoint by default.

  • goal_waypoint_rt_seed_ewrt_seed_tolerance – Vec3 protobuf of the tolerances for goal waypoint selection.

  • command_id – If not None, this continues an existing navigate_to command with the given ID. If None,

  • used. (navigation params will be) –

  • gps_navigation_params – API GPSNavigationParams. If not None, this will be interpreted as a GPS-based

  • GPS (navigation command. seed_tform_goal will be ignored and whatever goal is passed in using the) –

  • used.

Returns:

Command ID to use in feedback lookup.

Return type:

int

Raises:
navigate_to_anchor_async(seed_tform_goal, cmd_duration, route_params=None, travel_params=None, leases=None, timesync_endpoint=None, goal_waypoint_rt_seed_ewrt_seed_tolerance=None, command_id=None, gps_navigation_params=None, **kwargs)[source]

Async version of navigate_to_anchor().

navigation_feedback(command_id=0, **kwargs)[source]

Returns the feedback corresponding to the active route follow command.

Parameters:

command_id (int) – If blank, will return current command status. If filled out, will attempt to return that command status

Returns:

NavigationFeedbackResponse

Raises:

RpcError – Problem communicating with the robot.

navigation_feedback_async(command_id=0, **kwargs)[source]

Async version of navigation_feedback().

clear_graph(lease=None, **kwargs)[source]

Clears the local graph structure. Also erases any snapshots currently in RAM.

Parameters:

lease – Leases to show ownership of necessary resources. Will use the client’s leases by default.

Raises:
clear_graph_async(lease=None, **kwargs)[source]

Async version of clear_graph().

upload_graph(lease=None, graph=None, generate_new_anchoring=False, **kwargs)[source]

Uploads a graph to the server and appends to the existing graph.

Parameters:
  • lease – Leases to show ownership of necessary resources. Will use the client’s leases by default.

  • graph – Graph protobuf that represents the map with waypoints and edges.

  • generate_new_anchoring – Whether to generate an (overwrite the) anchoring on upload.

Returns:

The response, which includes waypoint and edge id’s sorted by whether it was cached.

Raises:
  • RpcError – Problem communicating with the robot.

  • UploadGraphError – Indicates a problem with the map provided.

  • IncompatibleSensorsError – The map was recorded with different sensors than the robot.

  • AreaCallbackError – The map includes area callback services not present on the robot.

  • LeaseUseError – Error using provided lease.

  • LicenseError – The robot’s license is not valid.

upload_graph_async(lease=None, graph=None, generate_new_anchoring=False, **kwargs)[source]

Async version of upload_graph().

upload_waypoint_snapshot(waypoint_snapshot, lease=None, **kwargs)[source]

Uploads large waypoint snapshot as a stream for a particular waypoint.

Parameters:
  • lease – Leases to show ownership of necessary resources. Will use the client’s leases by default.

  • waypoint_snapshot – WaypointSnapshot protobuf that will be stream-uploaded to the robot.

Returns:

The status of the upload request.

Raises:
upload_edge_snapshot(edge_snapshot, lease=None, **kwargs)[source]

Uploads large edge snapshot as a stream for a particular edge.

Parameters:
  • lease – Leases to show ownership of necessary resources. Will use the client’s leases by default.

  • edge_snapshot – EdgeSnapshot protobuf that will be stream-uploaded to the robot.

Returns:

The status of the upload request.

Raises:
download_graph(**kwargs)[source]

Downloads the graph from the server.

Returns:

The graph protobuf that represents the current map on the robot (with waypoints and edges).

Raises:

RpcError – Problem communicating with the robot

download_graph_async(**kwargs)[source]

Async version of download_graph().

download_waypoint_snapshot(waypoint_snapshot_id, download_images=False, do_not_download_point_cloud=False, **kwargs)[source]

Download a specific waypoint snapshot with streaming from the server.

Parameters:
  • waypoint_snapshot_id – WaypointSnapshot string ID for which snapshot to download from robot.

  • download_images – Boolean indicating whether to include images in the download.

  • do_not_download_point_cloud – Boolean indicating if point cloud data should not be downloaded.

Returns:

The WaypointSnapshot protobuf from the robot’s current map.

Raises:
download_edge_snapshot(edge_snapshot_id, **kwargs)[source]

Downloads a specific edge snapshot with streaming from the server.

Parameters:

edge_snapshot_id – EdgeSnapshot string ID for which snapshot to download from robot.

Returns:

The EdgeSnapshot protobuf from the robot’s current map.

Raises:
write_graph_and_snapshots(directory)[source]

Download the graph and snapshots from robot to the specified directory.

static generate_travel_params(max_distance, max_yaw, velocity_limit=None)[source]

Generate the API TravelParams for navigation requests.

Parameters:
  • max_distance – Distances (meters) threshold for when we’ve reached the final waypoint.

  • max_yaw – Angle (radians) threshold for when we’ve reached the final waypoint.

  • velocity_limit – SE2VelocityLimit protobuf message for the speed the robot should use.

Returns:

The API TravelParams protobuf message.

static build_route(waypoint_id_list, edge_id_list)[source]

Generate the API Route for navigation requests.

Parameters:
  • waypoint_id_list – List of waypoint id strings in which a route should pass through. The ids should be ordered from [start waypoint –> destination waypoint].

  • edge_id_list – List of the edge_id’s which should be in the same ordering as the waypoint list.

Returns:

The API Route protobuf message.

exception bosdyn.client.graph_nav.GraphNavServiceResponseError(response, error_message=None)[source]

Bases: ResponseError

General class of errors for the GraphNav Recording Service.

exception bosdyn.client.graph_nav.UploadWaypointSnapshotError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Errors related to uploading a waypoint snapshot

exception bosdyn.client.graph_nav.UploadGraphError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Errors related to uploading a graph.

exception bosdyn.client.graph_nav.MapTooLargeLicenseError(response, error_message=None)[source]

Bases: UploadGraphError

The map is too large for the license on the robot.

exception bosdyn.client.graph_nav.InvalidGraphError(response, error_message=None)[source]

Bases: UploadGraphError

The graph is invalid topologically, e.g. missing waypoints referenced by edges.

exception bosdyn.client.graph_nav.IncompatibleSensorsError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

The map was recorded with using a sensor configuration which is incompatible with the robot (for example, LIDAR configuration).

exception bosdyn.client.graph_nav.AreaCallbackMapError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

The map specified an area callback that is not registered or is faulted.

exception bosdyn.client.graph_nav.RequestAbortedError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Request was aborted by the system.

exception bosdyn.client.graph_nav.RequestFailedError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Request failed to complete by the system.

exception bosdyn.client.graph_nav.RobotFaultedError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Robot is experiencing a fault condition that prevents localization.

exception bosdyn.client.graph_nav.UnknownMapInformationError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

The given map information (waypoints,edges,routes) is unknown by the system.

exception bosdyn.client.graph_nav.TimeError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Errors associated with timestamps and time sync.

exception bosdyn.client.graph_nav.CommandExpiredError(response, error_message=None)[source]

Bases: TimeError

The command was received after its end time had already passed.

exception bosdyn.client.graph_nav.NoTimeSyncError(response, error_message=None)[source]

Bases: TimeError

Client has not performed timesync with robot.

exception bosdyn.client.graph_nav.TooDistantError(response, error_message=None)[source]

Bases: TimeError

The command was too far in the future.

exception bosdyn.client.graph_nav.RobotStateError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Errors associated with the current state of the robot.

exception bosdyn.client.graph_nav.IsRecordingError(response, error_message=None)[source]

Bases: RobotStateError

Cannot navigate a route while recording a map.

exception bosdyn.client.graph_nav.CannotModifyMapDuringRecordingError(response, error_message=None)[source]

Bases: RobotStateError

Cannot clear the map during recording. Call StopRecording first.

exception bosdyn.client.graph_nav.RobotImpairedError(response, error_message=None)[source]

Bases: RobotStateError

Robot has a critical perception or behavior fault and cannot navigate.

exception bosdyn.client.graph_nav.RouteError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Errors associated with the specified route.

exception bosdyn.client.graph_nav.ConstraintFaultError(response, error_message=None)[source]

Bases: RouteError

Route parameters contained a constraint fault.

exception bosdyn.client.graph_nav.InvalidEdgeError(response, error_message=None)[source]

Bases: RouteError

One or more edges do not connect to expected waypoints.

exception bosdyn.client.graph_nav.UnkownRouteElementsError(*args, **kwargs)[source]

Bases: RouteError

One or more waypoints/edges are not in the map.

Deprecated since version 3.0.0: Use UnknownRouteElementsError instead

exception bosdyn.client.graph_nav.UnknownRouteElementsError(*args, **kwargs)[source]

Bases: UnkownRouteElementsError

One or more waypoints/edges are not in the map.

exception bosdyn.client.graph_nav.NoPathError(response, error_message=None)[source]

Bases: RouteError

There is no path to the specified waypoint.

exception bosdyn.client.graph_nav.UnknownWaypointError(response, error_message=None)[source]

Bases: RouteError

One or more waypoints are not in the map.

exception bosdyn.client.graph_nav.NoAnchoringError(response, error_message=None)[source]

Bases: RouteError

There is no anchoring.

exception bosdyn.client.graph_nav.InvalidPoseError(response, error_message=None)[source]

Bases: RouteError

The requested pose is invalid, or known to be unachievable.

exception bosdyn.client.graph_nav.RouteNavigationError(response, error_message=None)[source]

Bases: GraphNavServiceResponseError

Errors related to how the robot navigates the route.

exception bosdyn.client.graph_nav.FeatureDesertError(response, error_message=None)[source]

Bases: RouteNavigationError

Route contained too many waypoints with low-quality features.

exception bosdyn.client.graph_nav.RouteNotUpdatingError(response, error_message=None)[source]

Bases: RouteNavigationError

Graph nav was unable to update and follow the specified route.

exception bosdyn.client.graph_nav.RobotLostError(response, error_message=None)[source]

Bases: RouteNavigationError

Cannot issue a navigation request when the robot is already lost.

exception bosdyn.client.graph_nav.InvalidGPSError(response, error_message=None)[source]

Bases: RouteNavigationError

Cannot issue the GPS command because it is invalid.

exception bosdyn.client.graph_nav.RobotNotLocalizedToRouteError(response, error_message=None)[source]

Bases: RouteNavigationError

The current localization doesn’t refer to any waypoint in the route (possibly uninitialized localization).

exception bosdyn.client.graph_nav.RobotStuckError(response, error_message=None)[source]

Bases: RouteNavigationError

The robot is stuck or unable to find a way forward. Resend the command with a new ID, or send a different command to try again.

exception bosdyn.client.graph_nav.UnrecongizedCommandError(*args, **kwargs)[source]

Bases: RouteNavigationError

Happens when you try to continue a command that was either expired, or had an unrecognized id.

Deprecated since version 3.1.0: Use UnrecognizedCommandError instead

exception bosdyn.client.graph_nav.UnrecognizedCommandError(*args, **kwargs)[source]

Bases: UnrecongizedCommandError

Happens when you try to continue a command that was either expired, or had an unrecognized id.