diff --git a/launch/step_4.launch.py b/launch/step_4.launch.py index bee9cc5330bf8a8a731dc426299d0698b596e4a2..34778daa2a82a418bc695455f2325677e8d3c9d7 100644 --- a/launch/step_4.launch.py +++ b/launch/step_4.launch.py @@ -15,5 +15,12 @@ def generate_launch_description(): namespace='', executable='step_4', name='square' - ) + ), + Node( + package='rqt_plot', + namespace='', + executable='rqt_plot', + arguments=['/turtle1/pose/theta'], + name='rqt' + ) ]) diff --git a/lesson_05/step_4.py b/lesson_05/step_4.py index 0aadceeac49995ffb174c923ca75f496161bf2eb..70dcee6d1d0816efdd5ea6aa3c6bfbd891a3e282 100644 --- a/lesson_05/step_4.py +++ b/lesson_05/step_4.py @@ -22,16 +22,17 @@ class RurMover(Node): self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) def pose_callback(self, msg): + Koeff=0.01 self.get_logger().info('Current heading: "%f"' % msg.theta) self.get_logger().info('Setpoint: "%f"' % self.desired_heading) 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) + msg_pub.angular.z = math.radians(90.0)-error*Koeff self.get_logger().info('Turn left') else: - msg_pub.angular.z = math.radians(-90.0) + msg_pub.angular.z = math.radians(-90.0)+error*Koeff self.get_logger().info('Turn right') self.publisher_twist.publish(msg_pub) @@ -51,4 +52,4 @@ def main(args=None): rclpy.shutdown() if __name__ == '__main__': - main() \ No newline at end of file + main()