diff --git a/lesson_04/basics.py b/lesson_04/basics.py deleted file mode 100644 index 3dfb7d818a22a9b132d4f3b756be11556f7b1557..0000000000000000000000000000000000000000 --- a/lesson_04/basics.py +++ /dev/null @@ -1,17 +0,0 @@ -import math - - -def to_degree(val): - return val*180/3.1415 - - -a = 3.14 -a = a/2 -print("В радианах:") -print(a) -print("В градусах:") -print(to_degree(a)) - -b = math.degrees(a) -print("В градусах библиотечное:") -print(b) diff --git a/lesson_04/square.py b/lesson_04/letter_Y.py similarity index 60% rename from lesson_04/square.py rename to lesson_04/letter_Y.py index 21f468769c8850956b023923ae3150ec03c1f7cc..5182d01f1864644a453bce540268efa33ac465af 100644 --- a/lesson_04/square.py +++ b/lesson_04/letter_Y.py @@ -12,23 +12,26 @@ class RurMover(Node): 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)) + def publish_twist(self, linear: float, angular=0.0): msg = Twist() msg.linear.x = float(linear) - msg.angular.z = math.radians(float(angular)) + msg.angular.z = angular self.publisher_twist.publish(msg) self.get_clock().sleep_for(Duration(seconds=1.0)) def main(self): - while True: - self.publish_twist(0, 90.0) - self.publish_twist(3.0, 0.0) + self.publish_twist(0, -math.pi / 3) + self.publish_twist(3.0) + self.publish_twist(0, 2 * math.pi / 3) + self.publish_twist(3.0) + self.publish_twist(0, math.pi) + self.publish_twist(3.0) + self.publish_twist(0, math.pi / 6) + self.publish_twist(3.5) def main(args=None): rclpy.init(args=args) - mover = RurMover() rclpy.spin(mover) @@ -36,5 +39,6 @@ def main(args=None): mover.destroy_node() rclpy.shutdown() -if __name__ == '__main__': - main() \ No newline at end of file + +if __name__ == "__main__": + main() diff --git a/lesson_04/mover.py b/lesson_04/mover.py deleted file mode 100644 index a61bebeaf1f00c8c51404fdd70aaa3c6ab7f58b3..0000000000000000000000000000000000000000 --- a/lesson_04/mover.py +++ /dev/null @@ -1,35 +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__('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): - pass - - -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/lesson_04/step_0.py b/lesson_04/step_0.py deleted file mode 100644 index 4fa986c610dea06468a7dabbf0f6d39a4d4c98fb..0000000000000000000000000000000000000000 --- a/lesson_04/step_0.py +++ /dev/null @@ -1,9 +0,0 @@ -import rclpy - - -def main(args=None): - rclpy.init(args=args) - rclpy.shutdown() - -if __name__ == '__main__': - main() \ No newline at end of file diff --git a/lesson_04/step_1.py b/lesson_04/step_1.py deleted file mode 100644 index 1a43ae0e46adc637e32df558cf0f2614d24b4ce6..0000000000000000000000000000000000000000 --- a/lesson_04/step_1.py +++ /dev/null @@ -1,18 +0,0 @@ -import rclpy -from rclpy.node import Node - -class RurMover(Node): - def __init__(self): - super().__init__('rur_mover') - -def main(args=None): - rclpy.init(args=args) - mover = RurMover() - - rclpy.spin(mover) - - mover.destroy_node() - rclpy.shutdown() - -if __name__ == '__main__': - main() diff --git a/lesson_04/step_2.py b/lesson_04/step_2.py deleted file mode 100644 index b62db7a20aa26c4a5d02c4adc2a304be38e5b06c..0000000000000000000000000000000000000000 --- a/lesson_04/step_2.py +++ /dev/null @@ -1,31 +0,0 @@ -import rclpy -from rclpy.node import Node - -from geometry_msgs.msg import Twist - - -class RurMover(Node): - def __init__(self): - super().__init__('rur_mover') - self.publisher_twist = self.create_publisher(Twist, 'turtle1/cmd_vel', 10) - self.main() - - def main(self): - msg = Twist() - msg.linear.x = 2.0 - msg.angular.z = -3.14 - self.publisher_twist.publish(msg) - - -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/lesson_04/step_3.py b/lesson_04/step_3.py deleted file mode 100644 index e4b7ac3df8409eaa49acc5377f947a4a66bc5193..0000000000000000000000000000000000000000 --- a/lesson_04/step_3.py +++ /dev/null @@ -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__('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, 90.0) - self.publish_twist(3, 0.0) - self.publish_twist(0, -120.0) - self.publish_twist(1, 0.0) - self.publish_twist(0, -120.0) - self.publish_twist(1, 0.0) - self.publish_twist(0, 60.0) - self.publish_twist(2, 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