From 71646e661ec69bfdeb2c8ebbe4341c2ac1bca51f Mon Sep 17 00:00:00 2001 From: sberestov Date: Tue, 22 Oct 2024 00:41:38 +0300 Subject: [PATCH 1/2] Modified setup.py to run new node --- setup.py | 1 + 1 file changed, 1 insertion(+) diff --git a/setup.py b/setup.py index 9e5dc57..20e9cc1 100644 --- a/setup.py +++ b/setup.py @@ -28,6 +28,7 @@ setup( 'step_3 = lesson_04.step_3:main', 'square = lesson_04.square:main', 'mover = lesson_04.mover:main', + 'letter = lesson_04.letter:main', ], }, ) -- GitLab From f64aacb7cf9de012f57abe56d02661ac787f138e Mon Sep 17 00:00:00 2001 From: sberestov Date: Tue, 22 Oct 2024 00:44:25 +0300 Subject: [PATCH 2/2] Added a node to draw letter S --- lesson_04/letter.py | 48 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 48 insertions(+) create mode 100644 lesson_04/letter.py diff --git a/lesson_04/letter.py b/lesson_04/letter.py new file mode 100644 index 0000000..16dd9ce --- /dev/null +++ b/lesson_04/letter.py @@ -0,0 +1,48 @@ +import rclpy +from rclpy.node import Node +from rclpy.duration import Duration + +from geometry_msgs.msg import Twist +import math + + +class RurMover(Node): + def __init__(self): + super().__init__('minimal_publisher') + self.publisher_twist = self.create_publisher(Twist, 'turtle1/cmd_vel', 10) + self.main() + + def publish_twist(self, linear, angular): + self.get_logger().info('Linear: "%d", angular: "%d"' % (linear, angular)) + msg = Twist() + msg.linear.x = float(linear) + msg.angular.z = math.radians(float(angular)) + self.publisher_twist.publish(msg) + self.get_clock().sleep_for(Duration(seconds=1.0)) + + def main(self): + self.publish_twist(0, 135.0) + self.publish_twist(1, 0.0) + self.publish_twist(0, 90.0) + self.publish_twist(1, 0.0) + self.publish_twist(0, 55.0) + self.publish_twist(1, 0.0) + self.publish_twist(0, 45.0) + self.publish_twist(1, 0.0) + self.publish_twist(0, -45.0) + self.publish_twist(1, 0.0) + self.publish_twist(0, -45.0) + self.publish_twist(1, 0.0) + +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