Skip to content

Commit

Permalink
namespacing support
Browse files Browse the repository at this point in the history
  • Loading branch information
Katie Hughes committed Feb 26, 2025
1 parent cdbd5fc commit a147da7
Show file tree
Hide file tree
Showing 3 changed files with 40 additions and 9 deletions.
19 changes: 19 additions & 0 deletions spot_ros2_control/config/spot_default_controllers_without_arm.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@ controller_manager:
forward_state_controller:
type: spot_controllers/ForwardStateController

spot_forward_controller:
type: spot_controllers/SpotForwardController


forward_position_controller:
ros__parameters:
Expand Down Expand Up @@ -51,3 +54,19 @@ forward_state_controller:
- position
- velocity
- effort

spot_forward_controller:
ros__parameters:
joints:
- front_left_hip_x
- front_left_hip_y
- front_left_knee
- front_right_hip_x
- front_right_hip_y
- front_right_knee
- rear_left_hip_x
- rear_left_hip_y
- rear_left_knee
- rear_right_hip_x
- rear_right_hip_y
- rear_right_knee
28 changes: 20 additions & 8 deletions spot_ros2_control/examples/set_gripper_gains.py
Original file line number Diff line number Diff line change
@@ -1,12 +1,15 @@
#!/usr/bin/env python
# Copyright (c) 2025 Boston Dynamics AI Institute LLC. All rights reserved.
import argparse
import time
from typing import Optional

import synchros2.process as ros_process
from sensor_msgs.msg import JointState
from synchros2.futures import unwrap_future
from synchros2.node import Node
from synchros2.subscription import Subscription
from synchros2.utilities import namespace_with

from spot_msgs.msg import JointCommand

Expand All @@ -17,21 +20,24 @@


class ExampleGripperStreaming:
def __init__(self, node: Node, robot_name: str) -> None:
def __init__(self, node: Node, robot_name: Optional[str] = None) -> None:
"""Initialize the example."""
self._node = node
self._logger = self._node.get_logger()
self._command_pub = self._node.create_publisher(JointCommand, "spot_forward_controller/joint_commands", 10)
self._robot_name = robot_name
self._command_pub = self._node.create_publisher(
JointCommand, namespace_with(self._robot_name, "spot_forward_controller/joint_commands"), 10
)
self._joint_command = JointCommand()
self._joint_command.name = [GRIPPER_JOINT_NAME]
self._joint_command.name = [namespace_with(self._robot_name, GRIPPER_JOINT_NAME)]
self._joint_command.k_q_p = [16.0]
self._joint_command.k_qd_p = [0.32]
self._joint_angles = Subscription(JointState, "low_level/joint_states")
self._joint_angles = Subscription(JointState, namespace_with(self._robot_name, "low_level/joint_states"))

def get_gripper_joint_angle(self) -> float:
"""Get the current gripper joint angle from the joint state topic"""
joint_state = unwrap_future(self._joint_angles.update, timeout_sec=5.0)
gripper_index = joint_state.name.index(GRIPPER_JOINT_NAME)
gripper_index = joint_state.name.index(namespace_with(self._robot_name, GRIPPER_JOINT_NAME))
gripper_position = joint_state.position[gripper_index]
return gripper_position

Expand Down Expand Up @@ -76,10 +82,16 @@ def open_and_close(self, duration_sec: float = 1.0, npoints: int = 50) -> None:
time.sleep(dt)


@ros_process.main()
def main() -> None:
def cli() -> argparse.ArgumentParser:
parser = argparse.ArgumentParser()
parser.add_argument("--robot", type=str, help="Namespace the driver is in", default=None)
return parser


@ros_process.main(cli())
def main(args: argparse.Namespace) -> None:
"""Run the example."""
example = ExampleGripperStreaming(node=main.node, robot_name="")
example = ExampleGripperStreaming(node=main.node, robot_name=args.robot)
example.open_and_close()
while True:
# Get gains to try out from the user.
Expand Down
2 changes: 1 addition & 1 deletion spot_ros2_control/launch/spot_ros2_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ def create_controllers_config(spot_name: str, has_arm: bool) -> str:
config = yaml.safe_load(template_file)
config[f"{spot_name}/controller_manager"] = config["controller_manager"]
del config["controller_manager"]
keys_to_namespace = ["forward_position_controller", "forward_state_controller"]
keys_to_namespace = ["forward_position_controller", "forward_state_controller", "spot_forward_controller"]

for key in keys_to_namespace:
key_joints = config[key]["ros__parameters"]["joints"]
Expand Down

0 comments on commit a147da7

Please sign in to comment.