diff --git a/spot_driver/package.xml b/spot_driver/package.xml index 859d5c716..f642052a0 100644 --- a/spot_driver/package.xml +++ b/spot_driver/package.xml @@ -32,7 +32,7 @@ tf2_ros tl_expected - bdai_ros2_wrappers + synchros2 python3-protobuf python3-tk robot_state_publisher diff --git a/spot_driver/spot_driver/calibrated_reregistered_hand_camera_depth_publisher.py b/spot_driver/spot_driver/calibrated_reregistered_hand_camera_depth_publisher.py index ddbcbd9b2..5ea6e698d 100644 --- a/spot_driver/spot_driver/calibrated_reregistered_hand_camera_depth_publisher.py +++ b/spot_driver/spot_driver/calibrated_reregistered_hand_camera_depth_publisher.py @@ -18,15 +18,15 @@ import argparse from typing import Optional -import bdai_ros2_wrappers.process as ros_process -import bdai_ros2_wrappers.scope as ros_scope import cv2 import numpy as np import open3d as o3d +import synchros2.process as ros_process +import synchros2.scope as ros_scope import yaml -from bdai_ros2_wrappers.context import wait_for_shutdown from cv_bridge import CvBridge from sensor_msgs.msg import Image +from synchros2.context import wait_for_shutdown class CalibratedReRegisteredHandCameraDepthPublisher: diff --git a/spot_driver/spot_driver/spot_alerts.py b/spot_driver/spot_driver/spot_alerts.py index 2e46fec78..faec02a78 100755 --- a/spot_driver/spot_driver/spot_alerts.py +++ b/spot_driver/spot_driver/spot_alerts.py @@ -2,10 +2,10 @@ from tkinter import messagebox from typing import Any, List, Optional -import bdai_ros2_wrappers.process as ros_process -from bdai_ros2_wrappers.node import Node +import synchros2.process as ros_process from rclpy.parameter import Parameter from rclpy.qos import QoSPresetProfiles +from synchros2.node import Node from spot_msgs.msg import ( # type: ignore BatteryStateArray, diff --git a/spot_driver/spot_driver/spot_ros2.py b/spot_driver/spot_driver/spot_ros2.py index 2c95747bc..625e8bee0 100644 --- a/spot_driver/spot_driver/spot_ros2.py +++ b/spot_driver/spot_driver/spot_ros2.py @@ -12,19 +12,12 @@ from enum import Enum from typing import Any, Callable, Dict, List, Optional, Union -import bdai_ros2_wrappers.process as ros_process import builtin_interfaces.msg import rclpy import rclpy.duration import rclpy.time +import synchros2.process as ros_process import tf2_ros -from bdai_ros2_wrappers.node import Node -from bdai_ros2_wrappers.single_goal_action_server import ( - SingleGoalActionServer, -) -from bdai_ros2_wrappers.single_goal_multiple_action_servers import ( - SingleGoalMultipleActionServers, -) from bosdyn.api import ( geometry_pb2, gripper_camera_param_pb2, @@ -69,6 +62,9 @@ from rclpy.timer import Rate from sensor_msgs.msg import JointState from std_srvs.srv import SetBool, Trigger +from synchros2.node import Node +from synchros2.single_goal_action_server import SingleGoalActionServer +from synchros2.single_goal_multiple_action_servers import SingleGoalMultipleActionServers import spot_driver.robot_command_util as robot_command_util diff --git a/spot_driver/test/pytests/conftest.py b/spot_driver/test/pytests/conftest.py index 162f12b95..95393029d 100644 --- a/spot_driver/test/pytests/conftest.py +++ b/spot_driver/test/pytests/conftest.py @@ -19,7 +19,6 @@ import tempfile import typing -import bdai_ros2_wrappers.scope as ros_scope import domain_coordinator import grpc import launch @@ -31,11 +30,12 @@ import launch_ros.substitutions import pytest import rclpy +import synchros2.scope as ros_scope import yaml -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.power_pb2 import PowerCommandRequest, PowerCommandResponse, PowerCommandStatus from bosdyn.api.robot_command_pb2 import RobotCommandResponse from bosdyn.api.robot_state_pb2 import PowerState +from synchros2.scope import ROSAwareScope import spot_wrapper.testing from spot_driver.spot_ros2 import SpotROS diff --git a/spot_driver/test/pytests/test_clear_behavior_fault.py b/spot_driver/test/pytests/test_clear_behavior_fault.py index 2b4c3a91b..55e1f4c4f 100644 --- a/spot_driver/test/pytests/test_clear_behavior_fault.py +++ b/spot_driver/test/pytests/test_clear_behavior_fault.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import ClearBehaviorFaultResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import ClearBehaviorFault # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_dock.py b/spot_driver/test/pytests/test_dock.py index 0ad9eeb7d..7c9582628 100644 --- a/spot_driver/test/pytests/test_dock.py +++ b/spot_driver/test/pytests/test_dock.py @@ -9,11 +9,11 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.basic_command_pb2 import RobotCommandFeedbackStatus, StandCommand from bosdyn.api.docking.docking_pb2 import DockingCommandFeedbackResponse, DockingCommandResponse from bosdyn.api.robot_command_pb2 import RobotCommandFeedbackResponse, RobotCommandResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import Dock # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_execute_dance.py b/spot_driver/test/pytests/test_execute_dance.py index 91fa8662c..cf62c182d 100644 --- a/spot_driver/test/pytests/test_execute_dance.py +++ b/spot_driver/test/pytests/test_execute_dance.py @@ -9,8 +9,6 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import ( ChoreographySequence, ChoreographyStatusResponse, @@ -20,6 +18,8 @@ from google.protobuf import text_format from rclpy.action import ActionClient from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.action import ExecuteDance # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_get_choreography_status.py b/spot_driver/test/pytests/test_get_choreography_status.py index b0a39bdec..e24782bbd 100644 --- a/spot_driver/test/pytests/test_get_choreography_status.py +++ b/spot_driver/test/pytests/test_get_choreography_status.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import ChoreographyStatusResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import GetChoreographyStatus # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_list_all_dances.py b/spot_driver/test/pytests/test_list_all_dances.py index e3fb4e7cc..982bf1a5d 100644 --- a/spot_driver/test/pytests/test_list_all_dances.py +++ b/spot_driver/test/pytests/test_list_all_dances.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import ListAllSequencesResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import ListAllDances # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_list_all_moves.py b/spot_driver/test/pytests/test_list_all_moves.py index 5f8ccce02..a0a70e146 100644 --- a/spot_driver/test/pytests/test_list_all_moves.py +++ b/spot_driver/test/pytests/test_list_all_moves.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import ListAllMovesResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import ListAllMoves # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_locomotion_mode.py b/spot_driver/test/pytests/test_locomotion_mode.py index 065f887ed..4124a21b3 100644 --- a/spot_driver/test/pytests/test_locomotion_mode.py +++ b/spot_driver/test/pytests/test_locomotion_mode.py @@ -9,8 +9,8 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import SetLocomotion # type: ignore diff --git a/spot_driver/test/pytests/test_max_velocity.py b/spot_driver/test/pytests/test_max_velocity.py index 0e5b49c05..f752a6d8e 100644 --- a/spot_driver/test/pytests/test_max_velocity.py +++ b/spot_driver/test/pytests/test_max_velocity.py @@ -9,8 +9,8 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import SetVelocity # type: ignore diff --git a/spot_driver/test/pytests/test_power_off.py b/spot_driver/test/pytests/test_power_off.py index 2d7114156..3dcb08904 100644 --- a/spot_driver/test/pytests/test_power_off.py +++ b/spot_driver/test/pytests/test_power_off.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import RobotCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_recorded_state_to_animation.py b/spot_driver/test/pytests/test_recorded_state_to_animation.py index b4f2523bf..b0e4a7bd3 100644 --- a/spot_driver/test/pytests/test_recorded_state_to_animation.py +++ b/spot_driver/test/pytests/test_recorded_state_to_animation.py @@ -9,8 +9,6 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.data_chunk_pb2 import DataChunk from bosdyn.api.geometry_pb2 import Quaternion, SE3Pose, Vec3 from bosdyn.api.header_pb2 import CommonError, ResponseHeader @@ -25,6 +23,8 @@ ) from google.protobuf.timestamp_pb2 import Timestamp from google.protobuf.wrappers_pb2 import DoubleValue +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import ChoreographyRecordedStateToAnimation # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_release.py b/spot_driver/test/pytests/test_release.py index f4bc00dd6..77cd52179 100644 --- a/spot_driver/test/pytests/test_release.py +++ b/spot_driver/test/pytests/test_release.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope @pytest.mark.usefixtures("spot_node", "simple_spot") diff --git a/spot_driver/test/pytests/test_robot_command.py b/spot_driver/test/pytests/test_robot_command.py index 4a1fbb3f2..33099aa39 100644 --- a/spot_driver/test/pytests/test_robot_command.py +++ b/spot_driver/test/pytests/test_robot_command.py @@ -9,14 +9,14 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.basic_command_pb2 import RobotCommandFeedbackStatus, StopCommand from bosdyn.api.full_body_command_pb2 import FullBodyCommand from bosdyn.api.robot_command_pb2 import RobotCommandFeedback, RobotCommandFeedbackResponse, RobotCommandResponse from bosdyn.client.robot_command import RobotCommandBuilder from bosdyn_msgs.conversions import convert from rclpy.action import ActionClient +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.action import RobotCommand as RobotCommandAction # type: ignore from spot_msgs.srv import RobotCommand as RobotCommandService # type: ignore diff --git a/spot_driver/test/pytests/test_robot_state.py b/spot_driver/test/pytests/test_robot_state.py index 6aaf58f5e..76e4ad3f5 100644 --- a/spot_driver/test/pytests/test_robot_state.py +++ b/spot_driver/test/pytests/test_robot_state.py @@ -3,11 +3,11 @@ import typing import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope -from bdai_ros2_wrappers.subscription import Subscription -from bdai_ros2_wrappers.utilities import namespace_with from sensor_msgs.msg import JointState +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope +from synchros2.subscription import Subscription +from synchros2.utilities import namespace_with from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_rollover.py b/spot_driver/test/pytests/test_rollover.py index b0f2055c1..f06a5a89c 100644 --- a/spot_driver/test/pytests/test_rollover.py +++ b/spot_driver/test/pytests/test_rollover.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import RobotCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_ros_interfaces.py b/spot_driver/test/pytests/test_ros_interfaces.py index 3414dbaa2..ba7185c53 100644 --- a/spot_driver/test/pytests/test_ros_interfaces.py +++ b/spot_driver/test/pytests/test_ros_interfaces.py @@ -3,8 +3,8 @@ import contextlib import unittest -import bdai_ros2_wrappers.scope as ros_scope import rclpy +import synchros2.scope as ros_scope from bosdyn_msgs.msg import RobotCommand, RobotCommandFeedback from std_srvs.srv import Trigger diff --git a/spot_driver/test/pytests/test_self_right.py b/spot_driver/test/pytests/test_self_right.py index 7d5f7b6b0..673acb41a 100644 --- a/spot_driver/test/pytests/test_self_right.py +++ b/spot_driver/test/pytests/test_self_right.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import RobotCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_sit.py b/spot_driver/test/pytests/test_sit.py index 617837246..cdb5cd182 100644 --- a/spot_driver/test/pytests/test_sit.py +++ b/spot_driver/test/pytests/test_sit.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import RobotCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_stair_mode.py b/spot_driver/test/pytests/test_stair_mode.py index 7f9c3f9b4..f6e40ffb4 100644 --- a/spot_driver/test/pytests/test_stair_mode.py +++ b/spot_driver/test/pytests/test_stair_mode.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from std_srvs.srv import SetBool +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope @pytest.mark.usefixtures("spot_node") diff --git a/spot_driver/test/pytests/test_stand.py b/spot_driver/test/pytests/test_stand.py index cd3ae57b8..707246a95 100644 --- a/spot_driver/test/pytests/test_stand.py +++ b/spot_driver/test/pytests/test_stand.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import RobotCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_start_recording_state.py b/spot_driver/test/pytests/test_start_recording_state.py index 4f40bfe2b..3429f2599 100644 --- a/spot_driver/test/pytests/test_start_recording_state.py +++ b/spot_driver/test/pytests/test_start_recording_state.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import StartRecordingStateResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import ChoreographyStartRecordingState # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_stop.py b/spot_driver/test/pytests/test_stop.py index ae539c2a1..6f70a4fd9 100644 --- a/spot_driver/test/pytests/test_stop.py +++ b/spot_driver/test/pytests/test_stop.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.robot_command_pb2 import RobotCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_stop_recording_state.py b/spot_driver/test/pytests/test_stop_recording_state.py index 6a73e1739..a72264cc1 100644 --- a/spot_driver/test/pytests/test_stop_recording_state.py +++ b/spot_driver/test/pytests/test_stop_recording_state.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import StopRecordingStateResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import ChoreographyStopRecordingState # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_undock.py b/spot_driver/test/pytests/test_undock.py index 0254ee1d8..2200d72b7 100644 --- a/spot_driver/test/pytests/test_undock.py +++ b/spot_driver/test/pytests/test_undock.py @@ -9,10 +9,10 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.docking.docking_pb2 import DockingCommandFeedbackResponse, DockingCommandResponse from std_srvs.srv import Trigger +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_upload_animation.py b/spot_driver/test/pytests/test_upload_animation.py index 84be473df..22e1d7334 100644 --- a/spot_driver/test/pytests/test_upload_animation.py +++ b/spot_driver/test/pytests/test_upload_animation.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import Animation, UploadAnimatedMoveResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import UploadAnimation # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_driver/test/pytests/test_upload_sequence.py b/spot_driver/test/pytests/test_upload_sequence.py index 7ce679a62..b203d2fbf 100644 --- a/spot_driver/test/pytests/test_upload_sequence.py +++ b/spot_driver/test/pytests/test_upload_sequence.py @@ -9,9 +9,9 @@ # pylint: disable=no-member import pytest -from bdai_ros2_wrappers.futures import wait_for_future -from bdai_ros2_wrappers.scope import ROSAwareScope from bosdyn.api.spot.choreography_sequence_pb2 import ChoreographySequence, UploadChoreographyResponse +from synchros2.futures import wait_for_future +from synchros2.scope import ROSAwareScope from spot_msgs.srv import UploadSequence # type: ignore from spot_wrapper.testing.fixtures import SpotFixture diff --git a/spot_examples/spot_examples/arm_simple.py b/spot_examples/spot_examples/arm_simple.py index 6b19b7bba..4a3129069 100644 --- a/spot_examples/spot_examples/arm_simple.py +++ b/spot_examples/spot_examples/arm_simple.py @@ -1,16 +1,16 @@ import argparse from typing import Optional -import bdai_ros2_wrappers.process as ros_process -import bdai_ros2_wrappers.scope as ros_scope -from bdai_ros2_wrappers.action_client import ActionClientWrapper -from bdai_ros2_wrappers.tf_listener_wrapper import TFListenerWrapper -from bdai_ros2_wrappers.utilities import namespace_with +import synchros2.process as ros_process +import synchros2.scope as ros_scope from bosdyn.api import geometry_pb2 from bosdyn.client import math_helpers from bosdyn.client.frame_helpers import GRAV_ALIGNED_BODY_FRAME_NAME, ODOM_FRAME_NAME from bosdyn.client.robot_command import RobotCommandBuilder from bosdyn_msgs.conversions import convert +from synchros2.action_client import ActionClientWrapper +from synchros2.tf_listener_wrapper import TFListenerWrapper +from synchros2.utilities import namespace_with from spot_msgs.action import RobotCommand # type: ignore diff --git a/spot_examples/spot_examples/batch_trajectory.py b/spot_examples/spot_examples/batch_trajectory.py index 9a4b89c62..f9adccb84 100644 --- a/spot_examples/spot_examples/batch_trajectory.py +++ b/spot_examples/spot_examples/batch_trajectory.py @@ -46,11 +46,8 @@ import time from typing import Callable, Optional, Tuple -import bdai_ros2_wrappers.process as ros_process -import bdai_ros2_wrappers.scope as ros_scope -from bdai_ros2_wrappers.action_client import ActionClientWrapper -from bdai_ros2_wrappers.tf_listener_wrapper import TFListenerWrapper -from bdai_ros2_wrappers.utilities import namespace_with +import synchros2.process as ros_process +import synchros2.scope as ros_scope from bosdyn.api import ( arm_command_pb2, basic_command_pb2, @@ -73,6 +70,9 @@ from bosdyn_msgs.conversions import convert from google.protobuf.wrappers_pb2 import DoubleValue from rclpy.node import Node +from synchros2.action_client import ActionClientWrapper +from synchros2.tf_listener_wrapper import TFListenerWrapper +from synchros2.utilities import namespace_with from tf2_ros import TransformStamped from spot_examples.simple_spot_commander import SimpleSpotCommander diff --git a/spot_examples/spot_examples/send_inverse_kinematics_requests.py b/spot_examples/spot_examples/send_inverse_kinematics_requests.py index f81332de2..8a8f02fb8 100644 --- a/spot_examples/spot_examples/send_inverse_kinematics_requests.py +++ b/spot_examples/spot_examples/send_inverse_kinematics_requests.py @@ -19,13 +19,10 @@ import argparse from typing import List -import bdai_ros2_wrappers.process as ros_process -import bdai_ros2_wrappers.scope as ros_scope import geometry_msgs.msg import numpy as np -from bdai_ros2_wrappers.action_client import ActionClientWrapper -from bdai_ros2_wrappers.tf_listener_wrapper import TFListenerWrapper -from bdai_ros2_wrappers.utilities import namespace_with +import synchros2.process as ros_process +import synchros2.scope as ros_scope from bosdyn.api.spot import inverse_kinematics_pb2, robot_command_pb2 from bosdyn.client.frame_helpers import ( BODY_FRAME_NAME, @@ -38,6 +35,9 @@ from bosdyn.client.robot_command import RobotCommandBuilder from bosdyn_msgs.conversions import convert from rclpy.node import Node +from synchros2.action_client import ActionClientWrapper +from synchros2.tf_listener_wrapper import TFListenerWrapper +from synchros2.utilities import namespace_with from tf2_ros import TransformBroadcaster, TransformStamped from spot_msgs.action import RobotCommand # type: ignore diff --git a/spot_examples/spot_examples/simple_spot_commander.py b/spot_examples/spot_examples/simple_spot_commander.py index d4ae7c80b..e8f85bc71 100644 --- a/spot_examples/spot_examples/simple_spot_commander.py +++ b/spot_examples/spot_examples/simple_spot_commander.py @@ -4,13 +4,13 @@ import logging from typing import Any, Dict, Optional -import bdai_ros2_wrappers.process as ros_process -import bdai_ros2_wrappers.scope as ros_scope import rclpy -from bdai_ros2_wrappers.utilities import fqn, namespace_with +import synchros2.process as ros_process +import synchros2.scope as ros_scope from rclpy.client import Client from rclpy.node import Node from std_srvs.srv import Trigger +from synchros2.utilities import fqn, namespace_with TRIGGER_SERVICES = [ "claim", diff --git a/spot_examples/spot_examples/walk_forward.py b/spot_examples/spot_examples/walk_forward.py index d1a6b618a..c6c562c98 100644 --- a/spot_examples/spot_examples/walk_forward.py +++ b/spot_examples/spot_examples/walk_forward.py @@ -2,16 +2,16 @@ import logging from typing import Optional -import bdai_ros2_wrappers.process as ros_process -import bdai_ros2_wrappers.scope as ros_scope -from bdai_ros2_wrappers.action_client import ActionClientWrapper -from bdai_ros2_wrappers.tf_listener_wrapper import TFListenerWrapper -from bdai_ros2_wrappers.utilities import fqn, namespace_with +import synchros2.process as ros_process +import synchros2.scope as ros_scope from bosdyn.client.frame_helpers import BODY_FRAME_NAME, VISION_FRAME_NAME from bosdyn.client.math_helpers import Quat, SE2Pose, SE3Pose from bosdyn.client.robot_command import RobotCommandBuilder from bosdyn_msgs.conversions import convert from rclpy.node import Node +from synchros2.action_client import ActionClientWrapper +from synchros2.tf_listener_wrapper import TFListenerWrapper +from synchros2.utilities import fqn, namespace_with from spot_msgs.action import RobotCommand # type: ignore