From c7495378408586154ef24b4cfa09f9330e3e6c02 Mon Sep 17 00:00:00 2001 From: Katie Hughes Date: Wed, 18 Dec 2024 16:58:05 -0500 Subject: [PATCH] remove hardcoded referernce in launchfile --- spot_driver/launch/spot_driver.launch.py | 2 +- spot_driver/test/src/conversions/test_robot_state.cpp | 9 +-------- 2 files changed, 2 insertions(+), 9 deletions(-) diff --git a/spot_driver/launch/spot_driver.launch.py b/spot_driver/launch/spot_driver.launch.py index fab0ef70..b7c6ec32 100644 --- a/spot_driver/launch/spot_driver.launch.py +++ b/spot_driver/launch/spot_driver.launch.py @@ -106,7 +106,7 @@ def launch_setup(context: LaunchContext, ld: LaunchDescription) -> None: ) ld.add_action(robot_state_publisher) - spot_robot_state_publisher_params = {"spot_name": spot_name, "preferred_odom_frame": "odom"} + spot_robot_state_publisher_params = {"spot_name": spot_name} spot_robot_state_publisher = launch_ros.actions.Node( package="spot_driver", executable="state_publisher_node", diff --git a/spot_driver/test/src/conversions/test_robot_state.cpp b/spot_driver/test/src/conversions/test_robot_state.cpp index f0919eb6..0712a166 100644 --- a/spot_driver/test/src/conversions/test_robot_state.cpp +++ b/spot_driver/test/src/conversions/test_robot_state.cpp @@ -343,14 +343,7 @@ TEST(RobotStateConversions, TestGetOdomTwist) { timestamp.set_nanos(0); addAcquisitionTimestamp(robot_state.mutable_kinematic_state(), timestamp); - auto* velocity_linear = robot_state.mutable_kinematic_state()->mutable_velocity_of_body_in_odom()->mutable_linear(); - velocity_linear->set_x(1.0); - velocity_linear->set_y(2.0); - velocity_linear->set_z(3.0); - auto* velocity_angular = robot_state.mutable_kinematic_state()->mutable_velocity_of_body_in_odom()->mutable_angular(); - velocity_angular->set_x(1.0); - velocity_angular->set_y(2.0); - velocity_angular->set_z(3.0); + addBodyVelocityOdom(robot_state.mutable_kinematic_state(), 1.0, 2.0, 3.0, 1.0, 2.0, 3.0); // GIVEN some nominal clock skew google::protobuf::Duration clock_skew;