From 4c59e1952b594cbf2e8ea323015c0d47d77d2560 Mon Sep 17 00:00:00 2001 From: ailognov Date: Mon, 11 Nov 2024 23:27:09 +0300 Subject: [PATCH 1/2] add new file --- lesson_06/step_1.py | 77 +++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 77 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..f8c4145 --- /dev/null +++ b/lesson_06/step_1.py @@ -0,0 +1,77 @@ +import rclpy +from rclpy.node import Node + +from geometry_msgs.msg import Twist +from geometry_msgs.msg import PoseStamped, Pose + +from tf_transformations import euler_from_quaternion +from std_msgs.msg import Float64 + + +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] + + +class RurMover(Node): + def __init__(self): + super().__init__('controller') + 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.PID_setpoint = self.create_publisher(Float64, '/pid/setpoint', 10) + self.PID_output = self.create_subscription(Float64, '/pid/output', self.PID_callback, 10) + self.PID_state = self.create_publisher(Float64, '/pid/state', 10) + + self.desired_heading = - math.pi / 2 + self.SIDE_TIME = 5.0 + self.LINEAR_SPEED = 2.0 + self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + + self.Points = [] + + 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.PID_state.publish(heading) + + desired_heading = Float64() + desired_heading.data = self.desired_heading + self.PID_setpoint.publish(desired_heading) + + + def PID_callback(self, msg): + + msg_pub = Twist() + msg_pub.linear.x = self.LINEAR_SPEED + msg_pub.angular.z = msg.data + 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 From bdccd395eb4628677cdbf8e17191d1d0bd4c222c Mon Sep 17 00:00:00 2001 From: ailognov Date: Mon, 11 Nov 2024 23:27:30 +0300 Subject: [PATCH 2/2] Config change --- config/control-config.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/config/control-config.yaml b/config/control-config.yaml index 80bbe66..39c82b9 100644 --- a/config/control-config.yaml +++ b/config/control-config.yaml @@ -4,8 +4,8 @@ angular: true clamp: 15.0 inverted: false - kd: 0.9 + kd: 3.0 ki: 0.0 - kp: 0.04 + kp: 10.0 start_type_description_service: true use_sim_time: false -- GitLab