From ec843fc74fb699b668f63637277e8c391663e461 Mon Sep 17 00:00:00 2001 From: Alina Date: Mon, 11 Nov 2024 11:26:13 +0300 Subject: [PATCH] Write node --- lesson_06/step_1.py | 70 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 70 insertions(+) create mode 100644 lesson_06/step_1.py diff --git a/lesson_06/step_1.py b/lesson_06/step_1.py new file mode 100644 index 0000000..e552a3a --- /dev/null +++ b/lesson_06/step_1.py @@ -0,0 +1,70 @@ +import rclpy +from rclpy.node import Node +from geometry_msgs.msg import Twist +from geometry_msgs.msg import PoseStamped, Pose +from std_msgs import Float64 +from tf_transformations import euler_from_quaternion +import math + +def angle_diff(a1, a2): + a = a1-a2 + return (a+math.pi)%(2*math.pi)-math.pi + +def get_yaw_from_quaternion(q): + return euler_from_quaternion([q.x, q.y, q.z, q.w])[2] + +def delt(t1,t2): + t=t2-t1 + return t + +class RurMover(Node): + def __init__(self): + super().__init__('controller') + self.heading=self.create_publisher(Float64,'/waterstrider/pid/state',10) + self.head_setpoint=self.create_publisher(Float64,'waterstrider/pid/setpoint',10) + self.result=self.create_subscription(Float64,'waterstrider/pid/output',self.pid_callback,10) + self.publisher_twist = self.create_publisher(Twist, '/waterstrider/twist_command', 10) + self.pose_subscriber = self.create_subscription(PoseStamped, '/waterstrider/ground_truth_to_tf_waterstrider/pose', self.pose_callback, 10) + + self.desired_heading = - math.pi / 2 + self.SIDE_TIME = 20.0 + self.LINEAR_SPEED = 0.5 + self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + + + def pose_callback(self, msg): + heading = Float64() + if self.desired_heading <= math.pi / 2: + heading.data = get_yaw_from_quaternion(msg.pose.orientation) + elif get_yaw_from_quaternion(msg.pose.orientation) < 0: + heading.data = 2 * math.pi + get_yaw_from_quaternion(msg.pose.orientation) + self.get_logger().info('current heading: "%f"' % heading.data) + self.get_logger().info('angle setpoint: "%f"' % self.desired_heading) + desired_heading = Float64() + desired_heading.data = self.desired_heading + self.heading.publish (heading) + self.head_setpoint.publish(desired_heading) + def pid_callback(self, msg): + pid_out = msg.data + msg_pub = Twist() + msg_pub.linear.x = self.LINEAR_SPEED + msg_pub.angular.z = pid_out + self.publisher_twist.publish(msg_pub) + + def pub_timer_callback(self): + self.desired_heading += math.pi / 2 + self.desired_heading %= 2 * math.pi + self.get_logger().info('New angle setpoint: "%f"' % self.desired_heading) + +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