Skip to content

Commit a24e481

Browse files
committed
change servo_server to servo_node
Signed-off-by: Hye-jong KIM <[email protected]>
1 parent 761abe0 commit a24e481

File tree

2 files changed

+4
-4
lines changed

2 files changed

+4
-4
lines changed

turtlebot3_manipulation_teleop/include/turtlebot3_manipulation_teleop/turtlebot3_manipulation_teleop.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -73,8 +73,8 @@
7373

7474
// Some constants used in the Servo Teleop demo
7575
const char BASE_TWIST_TOPIC[] = "cmd_vel";
76-
const char ARM_TWIST_TOPIC[] = "/servo_server/delta_twist_cmds";
77-
const char ARM_JOINT_TOPIC[] = "/servo_server/delta_joint_cmds";
76+
const char ARM_TWIST_TOPIC[] = "/servo_node/delta_twist_cmds";
77+
const char ARM_JOINT_TOPIC[] = "/servo_node/delta_joint_cmds";
7878

7979
const size_t ROS_QUEUE_SIZE = 10;
8080

turtlebot3_manipulation_teleop/src/turtlebot3_manipulation_teleop.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -55,9 +55,9 @@ KeyboardServo::KeyboardServo()
5555
nh_ = rclcpp::Node::make_shared("servo_keyboard_input");
5656

5757
servo_start_client_ =
58-
nh_->create_client<std_srvs::srv::Trigger>("/servo_server/start_servo");
58+
nh_->create_client<std_srvs::srv::Trigger>("/servo_node/start_servo");
5959
servo_stop_client_ =
60-
nh_->create_client<std_srvs::srv::Trigger>("/servo_server/stop_servo");
60+
nh_->create_client<std_srvs::srv::Trigger>("/servo_node/stop_servo");
6161

6262
base_twist_pub_ =
6363
nh_->create_publisher<geometry_msgs::msg::Twist>(BASE_TWIST_TOPIC, ROS_QUEUE_SIZE);

0 commit comments

Comments
 (0)