diff --git a/launch/step_4.launch.py b/launch/step_4.launch.py index bee9cc5330bf8a8a731dc426299d0698b596e4a2..cfdde73e8cd5de93b64b1ad467a5f1ea1f15c439 100644 --- a/launch/step_4.launch.py +++ b/launch/step_4.launch.py @@ -15,5 +15,11 @@ def generate_launch_description(): namespace='', executable='step_4', name='square' + ), + Node( + package='rqt_plot', + namespace='', + executable='rqt_plot', + name='rqt' ) ]) diff --git a/lesson_05/step_4.py b/lesson_05/step_4.py index 0aadceeac49995ffb174c923ca75f496161bf2eb..716649bbcdcd14af9bc112cbd0164a211b5106f8 100644 --- a/lesson_05/step_4.py +++ b/lesson_05/step_4.py @@ -13,12 +13,13 @@ def angle_diff(a1, a2): class RurMover(Node): def __init__(self): - super().__init__('minimal_publisher') + super().__init__('turtle_square_controller') self.publisher_twist = self.create_publisher(Twist, 'turtle1/cmd_vel', 10) self.pose_subscriber = self.create_subscription(Pose, 'turtle1/pose', self.pose_callback, 10) self.desired_heading = - math.pi / 2 self.SIDE_TIME = 5.0 self.LINEAR_SPEED = 0.5 + self.Kp_angular = 4.0 self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) def pose_callback(self, msg): @@ -27,12 +28,7 @@ class RurMover(Node): msg_pub = Twist() msg_pub.linear.x = self.LINEAR_SPEED error = angle_diff(self.desired_heading, msg.theta) - if error < 0: - msg_pub.angular.z = math.radians(90.0) - self.get_logger().info('Turn left') - else: - msg_pub.angular.z = math.radians(-90.0) - self.get_logger().info('Turn right') + msg_pub.angular.z = self.Kp_angular * error self.publisher_twist.publish(msg_pub) def pub_timer_callback(self):