diff --git a/config/control-config.yaml b/config/control-config.yaml index 80bbe66d87876352396a2d3238f2f8625038b722..e4fe34746b96eac21a80953dda564116456f5dc8 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: 1.0 ki: 0.0 - kp: 0.04 + kp: 8.0 start_type_description_service: true use_sim_time: false diff --git a/lesson_06/step_1.py b/lesson_06/step_1.py new file mode 100644 index 0000000000000000000000000000000000000000..03340ec00b6f6aaa6364dbc9f6d71329e5552d3b --- /dev/null +++ b/lesson_06/step_1.py @@ -0,0 +1,71 @@ +import math +from math import degrees +import rclpy +from rclpy.node import Node +from geometry_msgs.msg import Twist +from geometry_msgs.msg import PoseStamped +from std_msgs.msg import Float64 +from tf_transformations import euler_from_quaternion + + +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_state = self.create_publisher(Float64, '/waterstrider/pid/state', 10) + self.publisher_setpoint = self.create_publisher(Float64, '/waterstrider/pid/setpoint', 10) + self.result = self.create_subscription(Float64, '/waterstrider/pid/output', self.result_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.heading = None + self.desired_heading = -math.pi / 2 # Целевой угол + self.LINEAR_SPEED = 1.0 + self.SIDE_TIME = 10.0 + self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + + def pose_callback(self, msg): + self.heading = get_yaw_from_quaternion(msg.pose.orientation) # Текущий угол робота + mes_heading = Float64() + mes_heading.data = self.heading # Установка текущего угла в сообщение + self.publisher_state.publish(mes_heading) # Публикация текущего угла + + def pub_timer_callback(self): + self.desired_heading += math.pi / 2 # Увеличиваем целевой угол на 90 градусов + self.desired_heading %= 2 * math.pi # [0, 2π] + message = Float64() + message.data = self.desired_heading + self.publisher_setpoint.publish(message) # Публикуем новый целевой угол + + def result_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 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