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/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_3.py b/lesson_04/node.py similarity index 57% rename from lesson_04/step_3.py rename to lesson_04/node.py index e4b7ac3df8409eaa49acc5377f947a4a66bc5193..2023fcd49b318d186c65babfe8166e92d9f22717 100644 --- a/lesson_04/step_3.py +++ b/lesson_04/node.py @@ -19,15 +19,24 @@ class RurMover(Node): self.publisher_twist.publish(msg) self.get_clock().sleep_for(Duration(seconds=1.0)) - def main(self): + def main(self): # default direction: --> 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) + self.publish_twist(2.5, 0.0) + self.publish_twist(0, -90.0) + self.publish_twist(2.5, 0.0) + self.publish_twist(0, 180.0) + self.publish_twist(2.5, 0.0) + self.publish_twist(0, 90.0) + self.publish_twist(5, 0.0) + self.publish_twist(0, 90.0) + self.publish_twist(2.5, 0.0) + self.publish_twist(0, 180.0) + self.publish_twist(2.5, 0.0) + self.publish_twist(0, -90.0) + self.publish_twist(2.5, 0.0) + self.publish_twist(0, -90.0) + self.publish_twist(2.5, 0.0) + def main(args=None): diff --git a/lesson_04/square.py b/lesson_04/square.py deleted file mode 100644 index 21f468769c8850956b023923ae3150ec03c1f7cc..0000000000000000000000000000000000000000 --- a/lesson_04/square.py +++ /dev/null @@ -1,40 +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): - while True: - self.publish_twist(0, 90.0) - self.publish_twist(3.0, 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/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/setup.py b/setup.py index aa0b240a6c3f34d13a565dd0f713de9cc6690415..60d6f82b9fc6b23c2837a662a5ecd3196627c050 100644 --- a/setup.py +++ b/setup.py @@ -13,19 +13,14 @@ setup( ], install_requires=['setuptools'], zip_safe=True, - maintainer='mnc', - maintainer_email='m.chemodanov@noniusgroup.ru', + maintainer='gleb', + maintainer_email='dga@example.com', description='TODO: Package description', license='TODO: License declaration', tests_require=['pytest'], entry_points={ 'console_scripts': [ - 'step_0 = lesson_04.step_0:main', - 'step_1 = lesson_04.step_1:main', - 'step_2 = lesson_04.step_2:main', - 'step_3 = lesson_04.step_3:main', - 'square = lesson_04.square:main', - 'mover = lesson_04.mover:main', + 'node = lesson_04.node:main', ], }, )