Skip to content

Commit

Permalink
remove hardcoded referernce in launchfile
Browse files Browse the repository at this point in the history
  • Loading branch information
Katie Hughes committed Dec 18, 2024
1 parent 80522aa commit c749537
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 9 deletions.
2 changes: 1 addition & 1 deletion spot_driver/launch/spot_driver.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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",
Expand Down
9 changes: 1 addition & 8 deletions spot_driver/test/src/conversions/test_robot_state.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit c749537

Please sign in to comment.