diff --git a/lesson_06/pid_node.py b/lesson_06/pid_node.py index 6c390a5828b2978fbcf490f1b8891926e177a912..32e079a80f8e4dfd1f33f26d70fc5f91fc14dc69 100644 --- a/lesson_06/pid_node.py +++ b/lesson_06/pid_node.py @@ -18,9 +18,9 @@ class PID(Node): self.config['kp'] = self.declare_parameter('kp', 0.0).value self.config['ki'] = self.declare_parameter('ki', 0.0).value self.config['kd'] = self.declare_parameter('kd', 0.0).value - self.config['clamp'] = self.declare_parameter('clamp', 1.0).value - self.config['angular'] = self.declare_parameter('angular', False).value - self.config['inverted'] = self.declare_parameter('inverted', False).value + self.config['clamp'] = self.declare_parameter('clamp', 1.0).value #чтобы не подавать большое воздействие + self.config['angular'] = self.declare_parameter('angular', False).value #Угловое воздействие + self.config['inverted'] = self.declare_parameter('inverted', False).value #Инвертируем self.add_on_set_parameters_callback(self.parameter_callback) self.get_logger().warn(f"Parameters updated {self.config}") diff --git a/lesson_06/step_0.py b/lesson_06/step_0.py index c318b1005a99a72d19ee35d92b881158bd44153b..bb1356146a5f510b2fad12ff0a0fc17733f2e578 100644 --- a/lesson_06/step_0.py +++ b/lesson_06/step_0.py @@ -1,21 +1,16 @@ 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 - -import math +from geometry_msgs.msg import Twist, PoseStamped, Pose +from transformations import euler_from_quaternion +import math def angle_diff(a1, a2): - a = a1-a2 - return (a+math.pi)%(2*math.pi)-math.pi + 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') @@ -48,13 +43,10 @@ class RurMover(Node): def main(args=None): rclpy.init(args=args) - mover = RurMover() - rclpy.spin(mover) - mover.destroy_node() rclpy.shutdown() -if __name__ == '__main__': +if __name__ == 'main': main() \ No newline at end of file diff --git a/lesson_06/step_1.py b/lesson_06/step_1.py new file mode 100644 index 0000000000000000000000000000000000000000..a2bbb848f97c19c1b1b59eede3ef1d52bfa8ab8a --- /dev/null +++ b/lesson_06/step_1.py @@ -0,0 +1,97 @@ +import rclpy +from rclpy.node import Node +from geometry_msgs.msg import Twist, PoseStamped, Pose +from transformations import euler_from_quaternion +import math +import subprocess + +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.publisher_pose = self.create_publisher(PoseStamped, '/waterstrider/pose', 10) + self.previous_pose = None + self.radius = 5.0 # Задаём начальный радиус круга + self.radius_growth_rate = 5 # На сколько радиус увеличивается после каждого прокрута + self.SIDE_TIME = 10.0 + self.LINEAR_SPEED = 1.1 #Линейная скорость + self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + + def pose_callback(self, msg): + heading = get_yaw_from_quaternion(msg.pose.orientation) + self.get_logger().info('Current heading: "%f"' % heading) + + # вычисление линейной и угловой скоростей для кругового движения + linear_velocity = self.LINEAR_SPEED + angular_velocity = linear_velocity / self.radius # v = ωr -> ω = v/r + + msg_pub = Twist() + msg_pub.linear.x = linear_velocity + msg_pub.angular.z = angular_velocity + self.publisher_twist.publish(msg_pub) + + if self.previous_pose is None: + self.previous_pose = msg.pose + return + + # Получение текущих координат + current_x = msg.pose.position.x + current_y = msg.pose.position.y + current_z = msg.pose.position.z # Добавлено получение координаты Z + + # Получение предыдущих координат + previous_x = self.previous_pose.position.x + previous_y = self.previous_pose.position.y + + # Расчет дельты координат + delta_x = current_x - previous_x + delta_y = current_y - previous_y + + # Вычисление угла COG + cog_radians = math.atan2(delta_y, delta_x) + psi_x = cog_radians # Угол psi к оси X + + # Вывод значения геопозиции и COG в консоль + self.get_logger().info(f'X={current_x}, Y={current_y}, Z={current_z}, psi_X={psi_x}') + + # Обновление предыдущих координат + self.previous_pose = msg.pose + # Создание сообщения с текущими координатами и ориентацией + pose_msg = PoseStamped() + pose_msg.header.stamp = self.get_clock().now().to_msg() + pose_msg.header.frame_id = "world" # или другой frame_id, если необходимо + pose_msg.pose.position.x = current_x + pose_msg.pose.position.y = current_y + pose_msg.pose.position.z = current_z + + # Копирование ориентации из входящего сообщения + pose_msg.pose.orientation = msg.pose.orientation + + # Публикация сообщения + self.publisher_pose.publish(pose_msg) + + + def pub_timer_callback(self): + # Увеличиваем радиус следующего круга + self.radius += self.radius_growth_rate + self.get_logger().info('New radius: "%f"' % self.radius) + + + +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