From 389796bd6d9a79b042e01e04efb2522ecfcc4239 Mon Sep 17 00:00:00 2001 From: Anthony Baker Date: Wed, 26 Jul 2023 13:03:03 -0600 Subject: [PATCH] update unit test --- doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp b/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp index 4554604fac..530f9800a5 100644 --- a/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp +++ b/doc/tutorials/quickstart_in_rviz/test/bringup_test.cpp @@ -50,15 +50,15 @@ TEST_F(BringupTestFixture, BasicBringupTest) { // Check for several expected action servers auto control_client = rclcpp_action::create_client( - node_, "/panda_arm_controller/follow_joint_trajectory"); + node_, "/joint_trajectory_controller/follow_joint_trajectory"); EXPECT_TRUE(control_client->wait_for_action_server()); auto move_group_client = rclcpp_action::create_client(node_, "/move_action"); EXPECT_TRUE(move_group_client->wait_for_action_server()); // Send a trajectory request trajectory_msgs::msg::JointTrajectory traj_msg; - traj_msg.joint_names = { "panda_joint1", "panda_joint2", "panda_joint3", "panda_joint4", - "panda_joint5", "panda_joint6", "panda_joint7" }; + traj_msg.joint_names = { "joint_1", "joint_2", "joint_3", "joint_4", + "joint_5", "joint_6", "joint_7" }; trajectory_msgs::msg::JointTrajectoryPoint point_msg; point_msg.positions = { 0, -0.785, 0, -2.356, 0, 1.571, 0.785 }; point_msg.time_from_start.sec = 1;