diff --git a/launch/square.launch.py b/launch/square.launch.py new file mode 100644 index 0000000000000000000000000000000000000000..558068d65ffa8789b4e2aabf4e3b74c4eb4ea58d --- /dev/null +++ b/launch/square.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='square', + name='square' + ), + Node( + package='rqt_plot', + namespace='', + executable='rqt_plot', + name='rqt' + ) + ]) \ No newline at end of file diff --git a/lesson_05/square.py b/lesson_05/square.py new file mode 100644 index 0000000000000000000000000000000000000000..c70e9879724379fef2212817d5714d99c7c6cced --- /dev/null +++ b/lesson_05/square.py @@ -0,0 +1,49 @@ +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 = 13*error + self.publisher_twist.publish(msg_pub) + + def pub_timer_callback(self): + self.desired_heading += math.pi / 2 + self.desired_heading %= 2 * math.pi + self.get_logger().info('New angle setpoint: "%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 diff --git a/setup.py b/setup.py index 0e83277e26896894fdb28dc65870d33952f3406f..629c0c7658d70ed69c3df87041f7e1d9f62e2f99 100644 --- a/setup.py +++ b/setup.py @@ -27,6 +27,7 @@ setup( 'step_2 = lesson_05.step_2:main', 'step_3 = lesson_05.step_3:main', 'step_4 = lesson_05.step_4:main', + 'square = lesson_05.square:main', ], }, )