From d3d436c8998d742270fa4afeebdf7fc3f9a54887 Mon Sep 17 00:00:00 2001 From: IMaltzev Date: Tue, 29 Oct 2024 01:02:14 +0000 Subject: [PATCH] =?UTF-8?q?=D0=94=D0=BE=D0=B1=D0=B0=D0=B2=D0=BB=D0=B5?= =?UTF-8?q?=D0=BD=20rqt=20=D0=B8=20pid=20=D1=80=D0=B5=D0=B3=D1=83=D0=BB?= =?UTF-8?q?=D1=8F=D1=82=D0=BE=D1=80?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- launch/rqt_step_5.launch.py | 25 ++++++++++++++++++++ lesson_05/pid_step_5.py | 46 +++++++++++++++++++++++++++++++++++++ 2 files changed, 71 insertions(+) create mode 100644 launch/rqt_step_5.launch.py create mode 100644 lesson_05/pid_step_5.py diff --git a/launch/rqt_step_5.launch.py b/launch/rqt_step_5.launch.py new file mode 100644 index 0000000..da11915 --- /dev/null +++ b/launch/rqt_step_5.launch.py @@ -0,0 +1,25 @@ +from launch import LaunchDescription +from launch_ros.actions import Node + + +def generate_launch_description(): + return LaunchDescription([ + Node( + package='turtlesim', + namespace='', + executable='turtlesim_node', + name='sim' + ), + Node( + package='lesson_05', + namespace='', + executable='rqt_step_5', + name='square' + ), + Node( + package='rqt_plot', + namespace='', + executable='rqt_plot', + name='rqt' + ) + ]) diff --git a/lesson_05/pid_step_5.py b/lesson_05/pid_step_5.py new file mode 100644 index 0000000..83a6f20 --- /dev/null +++ b/lesson_05/pid_step_5.py @@ -0,0 +1,46 @@ +import rclpy +from rclpy.node import Node + +from geometry_msgs.msg import Twist +from turtlesim.msg import Pose +import math + + +def angle_diff(a1, a2): + a = a1-a2 + return (a+math.pi)%(2*math.pi)-math.pi + + +class RurMover(Node): + def __init__(self): + super().__init__('minimal_publisher') + 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.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + + def pose_callback(self, msg): + 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) + msg_pub.angular.z = 11 * error + self.publisher_twist.publish(msg_pub) + def pub_timer_callback(self): + + self.angle += math.pi / 2 + self.angle %= 2 * math.pi + self.get_logger().info('New angle set: "%f"' % self.desired_heading) + +def main(args=None): + rclpy.init(args=args) + mover = RurMover() + rclpy.spin(mover) + mover.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() \ No newline at end of file -- GitLab