This is an old revision of the document!
Spot ROS
The Spot robot comes with its own Spot SDK from Boston Dynamics, available in Python3 and C++. However, there is a ROS package that allows you to trigger most functionality of the robot using ROS messages, services and actions.
Installation
Installing the ROS package follows the same process as any other ROS package; git clone the repository, install dependencies, then build the package. Instructions from the Github Pages is here. It is recommended to use ROS Noetic for Python3 compatibility. Use a Docker container to get the correct ROS distro setup with all the distro-specific packages.
First, setup your catkin workspace, if you haven't already. Then, download the source code.
mkdir -p ~/catkin_ws/src source /opt/ros/noetic/setup.bash git clone https://github.com/heuristicus/spot_ros.git ~/catkin/src/spot_ros
Next, install the required dependencies with `rosdep`.
sudo apt install -y python3-rosdep rosdep install --from-paths ~/catkin_ws/src --ignore-src -y
Build the package with `catkin build`.
cd ~/catkin_ws/src catkin build
Source the built package.
source ~/catkin_ws/devel/setup.bash
Docker Usage
Alternatively, you can make use of pre-built Docker images generated by the CI pipeline.
Configuration
The ROS package has certain parameters that can be configured in `spot_driver/config/spot_ros.yaml`.
Parameter | Description |
---|---|
rates/robot_state | The robot's state (include joint angles) |
rates/metrics | The robot's metrics |
rates/lease | The robot's lease state |
rates/front_image | The image and depth image from the front camera |
rates/side_image | The image and depth image from the side cameras |
rates/loop_frequency | The image and depth image from the rear camera |
rates/point_cloud | The point cloud from the EAP lidar |
rates/hand_image | The image and depth image from the arm's hand camera |
rates/feedback | A feedback message with various information |
rates/mobility_params | Parameters indicating the robot's mobility state |
rates/check_subscribers | Check for subscribers on camera topics. Data is not published without subscribers |
There are also some flags that can be set to enable certain startup behaviour.
Parameter | Description |
---|---|
auto_claim | A boolean to automatically claim the body and e stop when the driver connects |
auto_power_on | A boolean to automatically power on the robot's motors when the driver connects |
auto_stand | A boolean to automatically stand the robot after the driver connects |
Lastly, some environmental variables you can set if you want to configure other nodes (Velodyne driver or teleop).
Variable | Default Value | Description |
---|---|---|
SPOT_VELODYNE_HOST | 192.168.131.20 | IP address of the VLP-16 sensor |
SPOT_JOY_DEVICE | /dev/input/js0 | The Linux joypad input device used by the joy_teleop node |
SPOT_JOY_CONFIG | spot_control/config/teleop.yaml | Joypad button/axis configuration file for joy_teleop |
SPOT_VELODYNE_AUTOLAUNCH | 1 | If 1 and SPOT_VELODYNE is also 1, the VLP16 ROS node will start automatically |
Running the spot_ros Driver
Before running the driver, you need to set the following parameters to authenticate with the robot.
Argument | Default | Description |
---|---|---|
username | dummyusername | Use this username to authenticate with spot |
password | dummypassword | Use this password to authenticate with spot |
hostname | 192.168.50.3 | The IP address at which spot can be found |
estop_timeout | 9.0 | Time allowed before rpc commands will time out. Comms between the |
robot and driver are checked at a rate of 1/3 of this time. If | ||
comms are down, a gentle estop will trigger | ||
autonomy_enabled | True | If false, some autonomy commands will be disabled for this run of |
the driver. This can only be changed on driver restart | ||
max_linear_velocity_x | 0 | Limit on linear velocity for moving forwards. 0 is whatever is |
specified by BD. | ||
max_linear_velocity_y | 0 | Limit on linear velocity for moving sideways. 0 is whatever is |
specified by BD. | ||
max_linear_velocity_z | 0 | Limit on angular velocity for rotation. 0 is whatever is specified |
by BD. | ||
allow_motion | True | If false, the robot starts with all motion disallowed and must have |
it enabled by calling a service or pressing a button in rviz |
To view the robot in RViz, use:
roslaunch spot_viz view_robot.launch
You should see something like this. The colour points represent the depth cloud produced by the 5 stereo cameras on the robot. The white dots will only be available after adding the PointCloud2 LIDAR data (/spot/lidar/points) to the RViz viewport.
Basic control of the robot can be done using the control panel on the right. This allows you to claim the lease, power on the robot and make it stand up. You can also command it to move to a specific location using the `2D Nav Goal` tool in RViz, or set a specific body pose to go to. When issuing any movement commands to the robot, you will need to claim the lease → power on → stand, before the commands will execute.
ROS Usage
Here are some examples on how to make use of the spot_ros package in an external ROS node, to control the robot.
Example 1
This was some example code used to traverse a GraphNav map and record fiducial positions along the way from the World Objects model of Spot.
#!/usr/bin/env python3 import typing import pickle import time import rospy import actionlib from actionlib_msgs.msg import GoalStatus from rosservice import get_service_class_by_name from std_msgs.msg import String from geometry_msgs.msg import PoseStamped from spot_msgs.msg import WorldObjectArray, WorldObject from spot_msgs.msg import AprilTagProperties from spot_msgs.msg import FrameTreeSnapshot, ParentEdge from spot_msgs.msg import NavigateInitAction, NavigateInitGoal from spot_msgs.msg import NavigateToAction, NavigateToGoal from spot_msgs.srv import ListGraphResponse from std_srvs.srv import TriggerRequest from fiducial import Fiducial class SpotNav: def __init__(self): self.world_objects = None self.fiducials_seen: typing.Dict[int, typing.List["Fiducial"]] = {} self.waypoint_fiducial: typing.Dict[str, typing.List["Fiducial"]] = {} def initialize_subscribers(self): """Initialize ROS subscribers""" # Create a subscriber for the /spot/world_objects topic for WorldObjectArray messages self.world_objects_sub = rospy.Subscriber( "/spot/world_objects", WorldObjectArray, self.world_objects_callback ) def initialize_publishers(self): """Initialize ROS publishers""" self.reached_waypoint_pub = rospy.Publisher( "/spot/nav/reached_waypoint", String, queue_size=1 ) def initialize_action_clients(self): """Initialize ROS action clients""" # Create an action client for the /spot/navigate_to action self.navigate_to_client = actionlib.SimpleActionClient( "/spot/navigate_to", NavigateToAction ) # Create an action client for the /spot/navigate_init action self.navigate_init_client = actionlib.SimpleActionClient( "/spot/navigate_init", NavigateInitAction ) def world_objects_callback(self, msg: WorldObjectArray): # Save the message to a class variable tracking the fiducials in the message self.world_objects: typing.List[WorldObject] = msg.world_objects # Iterate through the fiducials in the message, append the x,y,z coordinates to a dictionary for world_object in self.world_objects: april_tag: AprilTagProperties = world_object.apriltag_properties latest_snapshot: FrameTreeSnapshot = world_object.frame_tree_snapshot # Check if april_tag is None if april_tag is None: continue # Create the FrameTreeSnapshot as a dictionary frame_tree_snapshot: typing.Dict[str, PoseStamped] = {} for child, parent_edge in zip( latest_snapshot.child_edges, latest_snapshot.parent_edges ): parent_edge_transform = PoseStamped() parent_edge_transform.header.stamp = world_object.acquisition_time parent_edge_transform.header.frame_id = parent_edge.parent_frame_name parent_edge_transform.pose = parent_edge.parent_tform_child frame_tree_snapshot[child] = parent_edge_transform april_tag_pose = frame_tree_snapshot[f"fiducial_{april_tag.tag_id}"] april_tag_pose_filtered = frame_tree_snapshot[ f"filtered_fiducial_{april_tag.tag_id}" ] # Build the april_tag into the Fiducial class fiducial = Fiducial( tag_id=april_tag.tag_id, dim_x=april_tag.x, dim_y=april_tag.y, fiducial_pose=april_tag_pose, filtered_fiducial_pose=april_tag_pose_filtered, pose_covariance=april_tag.detection_covariance, pose_covariance_frame=april_tag.detection_covariance_reference_frame, ) # Save the fiducial to the class variable if fiducial.tag_id in self.fiducials_seen: self.fiducials_seen[fiducial.tag_id].append(fiducial) else: self.fiducials_seen[fiducial.tag_id] = [fiducial] rospy.logdebug( f"fiducial: {fiducial.tag_id}\n position_x: {fiducial.fiducial_pose.pose.position.x:.2f}\n filtered_position_x: {fiducial.filtered_fiducial_pose.pose.position.x:.2f}" ) def call_service(self, service_name: str, *args, **kwargs): """Call a service and wait for it to be available""" try: rospy.wait_for_service(service_name) service_type = get_service_class_by_name(service_name) proxy = rospy.ServiceProxy(service_name, service_type) return proxy(*args, **kwargs) except rospy.ServiceException as e: rospy.logerr("Service call failed: %s" % e) def walk_current_graph(self): """Walk the current graph in GraphNav""" rospy.loginfo("Walking the current graph") # Call the ListGraph service list_graph: ListGraphResponse = self.call_service("/spot/list_graph") waypoints = list_graph.waypoint_ids # Call the /spot/navigate_init action navigate_init_goal = NavigateInitGoal( upload_path="", initial_localization_fiducial=True, initial_localization_waypoint="mm", ) self.navigate_init_client.send_goal(navigate_init_goal) self.navigate_init_client.wait_for_result() # Check if the action succeeded if self.navigate_init_client.get_state() == GoalStatus.SUCCEEDED: rospy.loginfo("NavigateInit action succeeded") for waypoint in waypoints: # Call the /spot/navigate_to action navigate_to_goal = NavigateToGoal(navigate_to=waypoint) self.navigate_to_client.send_goal(navigate_to_goal) self.navigate_to_client.wait_for_result() # Check if the action succeeded if self.navigate_to_client.get_state() == GoalStatus.SUCCEEDED: rospy.loginfo(f"NavigateTo {waypoint} action succeeded") latest_world_objects_msg = rospy.wait_for_message( "/spot/world_objects", WorldObjectArray ) latest_fiducial = self.extract_fiducials(latest_world_objects_msg) if waypoint in self.waypoint_fiducial: self.waypoint_fiducial[waypoint].append(latest_fiducial) else: self.waypoint_fiducial[waypoint] = [latest_fiducial] # Publish to the /spot/nav/reached_waypoint topic self.reached_waypoint_pub.publish(waypoint) time.sleep(0.5) def extract_fiducials(self, msg: WorldObjectArray) -> typing.List["Fiducial"]: self.world_objects: typing.List[WorldObject] = msg.world_objects fiducial_list = [] # Iterate through the fiducials in the message, append the x,y,z coordinates to a dictionary for world_object in self.world_objects: april_tag: AprilTagProperties = world_object.apriltag_properties latest_snapshot: FrameTreeSnapshot = world_object.frame_tree_snapshot # Check if april_tag is None if april_tag is None: continue # Create the FrameTreeSnapshot as a dictionary frame_tree_snapshot: typing.Dict[str, PoseStamped] = {} for child, parent_edge in zip( latest_snapshot.child_edges, latest_snapshot.parent_edges ): parent_edge_transform = PoseStamped() parent_edge_transform.header.stamp = world_object.acquisition_time parent_edge_transform.header.frame_id = parent_edge.parent_frame_name parent_edge_transform.pose = parent_edge.parent_tform_child frame_tree_snapshot[child] = parent_edge_transform # Use tf2 to get the april_tag pose in the body frame april_tag_pose = frame_tree_snapshot[f"fiducial_{april_tag.tag_id}"] april_tag_pose_filtered = frame_tree_snapshot[ f"filtered_fiducial_{april_tag.tag_id}" ] # Build the april_tag into the Fiducial class fiducial = Fiducial( tag_id=april_tag.tag_id, dim_x=april_tag.x, dim_y=april_tag.y, fiducial_pose=april_tag_pose, filtered_fiducial_pose=april_tag_pose_filtered, pose_covariance=april_tag.detection_covariance, pose_covariance_frame=april_tag.detection_covariance_reference_frame, ) # Append the fiducial to the list fiducial_list.append(fiducial) return fiducial_list def startup(self): rospy.loginfo("SpotNav robot starting up") # Call the /spot/claim, /spot/power_on, /spot/stand service self.call_service("/spot/claim", TriggerRequest()) self.call_service("/spot/power_on", TriggerRequest()) def shutdown(self): rospy.loginfo("SpotNav node shutting down") # Save the fiducials to a pickle file with open(f"fiducials_seen.pickle_{time.time()}", "wb") as f: pickle.dump(self.fiducials_seen, f) with open(f"waypoint_fiducial.pickle_{time.time()}", "wb") as f: pickle.dump(self.waypoint_fiducial, f) # Call the /spot/sit, /spot/power_off, /spot/release service self.call_service("/spot/sit", TriggerRequest()) time.sleep(5) self.call_service("/spot/power_off", TriggerRequest()) self.call_service("/spot/release", TriggerRequest()) def main(self): rospy.init_node("spot_nav", anonymous=True) self.rates = rospy.get_param("~rates", {}) if "loop_frequency" in self.rates: loop_rate = self.rates["loop_frequency"] else: loop_rate = 50 # Initialize the node rate = rospy.Rate(loop_rate) rospy.loginfo("SpotNav node started") self.initialize_subscribers() self.initialize_publishers() self.initialize_action_clients() rospy.on_shutdown(self.shutdown) # Walk the current graph self.startup() self.walk_current_graph() while not rospy.is_shutdown(): rate.sleep() if __name__ == "__main__": spot_nav = SpotNav() spot_nav.main() </code>
ROS Topics
The available ROS topics and thier descriptions are in this section.
Topic | Type | Description |
---|---|---|
/spot/claim | Trigger | Claim the lease |
/spot/release | Trigger | Release the lease |
/spot/self_right | Trigger | Flip onto the legs |
/spot/sit | Trigger | Sit the robot |
/spot/stand | Trigger | Stand the robot |
/spot/power_on | Trigger | Enable motor power |
/spot/power_off | Trigger | Disable motor power |
/spot/estop/hard | Trigger | Trigger the estop immediately |
/spot/estop/gentle | Trigger | Trigger the estop gracefully |
/spot/estop/release | Trigger | Release the estop |
/spot/allow_motion | SetBool | Enable or disable motion |
/spot/stair_mode | SetBool | Enable or disable stair climbing mode |
/spot/locomotion_mode | SetLocomotion | Set locomotion_mode |
/spot/swing_height | SetSwingHeight | Set swing_height mode |
/spot/velocity_limit | SetVelocity | Set velocity_limit as Twist message |
/spot/clear_behavior_fault | ClearBehaviorFault | Clear faults by id |
/spot/terrain_params | SetTerrainParams | Set ground_mu_hint and grated surfaces mode |
/spot/obstacle_params | SetObstacleParams | Set obstacle avoidance parameters |
/spot/posed_stand | PosedStand | Set body height and pose |
/spot/list_graph | ListGraph | Get the list of waypoints in the active graph |
/spot/download_graph | DownloadGraph | Download the list of waypoints in the active graph |
/spot/navigate_init | NavigateInit | Localization with a fiducial in the provided map |
/spot/graph_close_loops | GraphCloseLoops | Request loop closure in the active graph |
/spot/optimize_graph_anchoring | Trigger | Request anchor optimization in the active graph |
/spot/roll_over_right | Trigger | Roll body over to the right |
/spot/roll_over_left | Trigger | Roll body over to the left |
/spot/dock | Dock | Dock at dock_id |
/spot/undock | Trigger | Undock the robot |
/spot/docking_state | GetDockState | Get the dock_state of the robot |
/spot/spot_check | SpotCheck | Run Spot Check self-calibration |
/spot/arm_stow | Trigger | Arm stow position |
/spot/arm_unstow | Trigger | Arm unstow position |
/spot/gripper_open | Trigger | Gripper open position |
/spot/gripper_close | Trigger | Gripper close position |
/spot/arm_carry | Trigger | Arm carry position |
/spot/gripper_angle_open | GripperAngleMove | Gripper open to specific angle |
/spot/arm_joint_move | ArmJointMovement | Arm move to specific angle for each joint |
/spot/force_trajectory | ArmForceTrajectory | Arm move as a wrench |
/spot/gripper_pose | HandPose | Gripper move to Pose in a specific frame |
/spot/grasp_3d | Grasp3d | Execute a pick at a Position in a specific frame |
/spot/arm_gaze | Trigger | Arm gaze towards the front, for demonstration |
/spot/stop | Trigger | Stop the robot |
/spot/locked_stop | Trigger | Stop the robot and disallow motion |
/spot/spot_ros/tf2_frames | Trigger | Get tf2 transformation frames as a FrameGraph |
Frequently Asked Questions (FAQ)
Question 1: How do I upload a Docker container to Spot?
Answer: Follow this guide on how to use Portainer on the Spot CORE.
Question 2: Does Spot have access to the Internet?
Answer: No, not unless you specifically set it up.
Further Reading and Resources
This section includes links to additional documentation, tutorials, and other resources.