From 8863c4f370415e91dfa49d7b2ce9942ac963d259 Mon Sep 17 00:00:00 2001 From: RTarasov Date: Thu, 17 Oct 2024 18:51:29 +0300 Subject: [PATCH 1/3] Add mover.py to draw letter T in turtlesim --- lesson_04/mover.py | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/lesson_04/mover.py b/lesson_04/mover.py index a61bebe..03f0ed6 100644 --- a/lesson_04/mover.py +++ b/lesson_04/mover.py @@ -8,12 +8,11 @@ import math class RurMover(Node): def __init__(self): - super().__init__('minimal_publisher') + super().__init__('DrawerRPublisher') 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)) @@ -21,8 +20,18 @@ class RurMover(Node): self.get_clock().sleep_for(Duration(seconds=1.0)) def main(self): - pass - + #Рисую букву Т(Первая буква моей фамилии) + self.publish_twist(0, 90.0) + self.publish_twist(3, 0.0) + self.publish_twist(0, -90.0) + self.publish_twist(1.5, 0.0) + self.publish_twist(0, 180.0) + self.publish_twist(3, 0.0) + self.publish_twist(0, 180) + self.publish_twist(1.5, 0) + self.publish_twist(0, -90) + self.publish_twist(3, 0) + self.publish_twist(0, 90) def main(args=None): rclpy.init(args=args) -- GitLab From 63b8e3c24d74f12ecf2f9135eef48470a06af356 Mon Sep 17 00:00:00 2001 From: RTarasov Date: Thu, 17 Oct 2024 19:06:52 +0300 Subject: [PATCH 2/3] change mover.py to draw T --- lesson_04/mover.py | 44 -------------------------------------------- 1 file changed, 44 deletions(-) diff --git a/lesson_04/mover.py b/lesson_04/mover.py index 03f0ed6..e69de29 100644 --- a/lesson_04/mover.py +++ b/lesson_04/mover.py @@ -1,44 +0,0 @@ -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__('DrawerRPublisher') - self.publisher_twist = self.create_publisher(Twist, 'turtle1/cmd_vel', 10) - self.main() - - def publish_twist(self, 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, 90.0) - self.publish_twist(3, 0.0) - self.publish_twist(0, -90.0) - self.publish_twist(1.5, 0.0) - self.publish_twist(0, 180.0) - self.publish_twist(3, 0.0) - self.publish_twist(0, 180) - self.publish_twist(1.5, 0) - self.publish_twist(0, -90) - self.publish_twist(3, 0) - self.publish_twist(0, 90) - -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 From e19e2312eb49f84baa3fd0111d512885bab15879 Mon Sep 17 00:00:00 2001 From: RTarasov Date: Thu, 17 Oct 2024 19:07:27 +0300 Subject: [PATCH 3/3] Change mover.py to draw T letter --- lesson_04/mover.py | 44 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) diff --git a/lesson_04/mover.py b/lesson_04/mover.py index e69de29..03f0ed6 100644 --- a/lesson_04/mover.py +++ b/lesson_04/mover.py @@ -0,0 +1,44 @@ +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__('DrawerRPublisher') + self.publisher_twist = self.create_publisher(Twist, 'turtle1/cmd_vel', 10) + self.main() + + def publish_twist(self, 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, 90.0) + self.publish_twist(3, 0.0) + self.publish_twist(0, -90.0) + self.publish_twist(1.5, 0.0) + self.publish_twist(0, 180.0) + self.publish_twist(3, 0.0) + self.publish_twist(0, 180) + self.publish_twist(1.5, 0) + self.publish_twist(0, -90) + self.publish_twist(3, 0) + self.publish_twist(0, 90) + +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