From fd9676e28f808a3476f71ee88baf9e0fb34c6811 Mon Sep 17 00:00:00 2001 From: Bulka Date: Sun, 21 Jan 2024 15:52:00 +0300 Subject: [PATCH] =?UTF-8?q?=D1=87=D0=B5=D1=80=D0=B5=D0=BF=D0=B0=D1=85?= =?UTF-8?q?=D0=B0=20=D1=80=D0=B8=D1=81=D1=83=D0=B5=D1=82=20=D0=B2=D1=83?= =?UTF-8?q?=D0=BB=D0=BA=D0=B0=D0=BD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- lesson_04/Test1.py | 47 ++++++++++++++++++++++++++++++++++++++++++++++ setup.py | 1 + 2 files changed, 48 insertions(+) create mode 100644 lesson_04/Test1.py diff --git a/lesson_04/Test1.py b/lesson_04/Test1.py new file mode 100644 index 0000000..04a5faa --- /dev/null +++ b/lesson_04/Test1.py @@ -0,0 +1,47 @@ +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): + 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, 30.0) + self.publish_twist(3, 40.0) + self.publish_twist(0, -120.0) + self.publish_twist(1, 50.0) + self.publish_twist(0, -120.0) + self.publish_twist(1, 10.0) + self.publish_twist(0, 20.0) + self.publish_twist(2, 5.0) + self.publish_twist(0, -115.0) + self.publish_twist(3, 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 diff --git a/setup.py b/setup.py index aa0b240..30ced9e 100644 --- a/setup.py +++ b/setup.py @@ -26,6 +26,7 @@ setup( 'step_3 = lesson_04.step_3:main', 'square = lesson_04.square:main', 'mover = lesson_04.mover:main', + 'test = lesson_04.Test1:main', ], }, ) -- GitLab