diff --git a/ros2_ws/src/iiwa_inverse_kinematics/iiwa_inverse_kinematics/inverse_kinematics_node.py b/ros2_ws/src/iiwa_inverse_kinematics/iiwa_inverse_kinematics/inverse_kinematics_node.py
index f7354350ca37a89983c642dedb52f1e534e0ba62..5714acc9cb7d0e2d18fcb93782a58dbea3970c66 100644
--- a/ros2_ws/src/iiwa_inverse_kinematics/iiwa_inverse_kinematics/inverse_kinematics_node.py
+++ b/ros2_ws/src/iiwa_inverse_kinematics/iiwa_inverse_kinematics/inverse_kinematics_node.py
@@ -16,7 +16,7 @@ class InverseKinematicsNode(Node):
         super().__init__('inverse_kinematics_node')
         self.subscription = self.create_subscription(
             Pose,
-            'target_pose',
+            '/kuka_iiwa/target_pose',
             self.pose_callback,
             10)
         self.publisher = self.create_publisher(JointTrajectory, '/iiwa_arm_controller/joint_trajectory', 10)
@@ -66,7 +66,6 @@ class InverseKinematicsNode(Node):
 
         if success:
             self.joint_angles = joint_angles
-            self.get_logger().info('Joint angles: "%s"' %self.joint_angles)
 
             joint_trajectory_msg = JointTrajectory()
             joint_trajectory_msg.joint_names = self.joint_names