diff --git a/config/control-config.yaml b/config/control-config.yaml index 80bbe66d87876352396a2d3238f2f8625038b722..f1c9764d04ccdcdb87b19068092eeb99ddc2bb9b 100644 --- a/config/control-config.yaml +++ b/config/control-config.yaml @@ -2,10 +2,10 @@ pid: ros__parameters: angular: true - clamp: 15.0 + clamp: 175.0 inverted: false - kd: 0.9 - ki: 0.0 - kp: 0.04 + kd: 50000.0 + ki: 1000000.0 + kp: 9000.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..d8d3861e8e761f93a4f397b249fd35ca160f5f9f --- /dev/null +++ b/lesson_06/step_1.py @@ -0,0 +1,72 @@ +import rclpy +from rclpy.node import Node + +from geometry_msgs.msg import Twist +from geometry_msgs.msg import PoseStamped, Pose + +from std_msgs.msg 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] + + +class RurMover(Node): + def __init__(self): + super().__init__('controller') + self.publisher_twist = self.create_publisher(Twist, '/waterstrider/twist_command', 10) + self.pid_setpoint = self.create_publisher(Float64, '/waterstrider/pid/setpoint', 10) + self.pid_state = self.create_publisher(Float64, '/waterstrider/pid/state', 10, ) + self.pid_output= self.create_subscription(Float64, '/waterstrider/pid/output', self.pid_output, 10) + self.pose_subscriber = self.create_subscription(PoseStamped, '/waterstrider/ground_truth_to_tf_waterstrider/pose', self.pose_callback, 10) + self.heading = 0 + self.n = 0 + self.desired_heading = - math.pi / 2 + self.SIDE_TIME = 10.0 + self.LINEAR_SPEED = 1.0 + self.timer = self.create_timer(self.SIDE_TIME, self.pub_timer_callback) + + def pid_output(self, msg): + angle_spd = msg.data + msg_pub = Twist() + msg_pub.linear.x = self.LINEAR_SPEED + msg_pub.angular.z = math.radians(angle_spd) + self.get_logger().info(f'Turn speed: {angle_spd:.3f}') + self.publisher_twist.publish(msg_pub) + + def pose_callback(self, msg): + self.heading = get_yaw_from_quaternion(msg.pose.orientation)+math.pi + self.get_logger().info('Current heading: "%f"' % self.heading) + self.get_logger().info('Setpoint: "%f"' % self.desired_heading) + self.diff = angle_diff(self.heading, self.desired_heading) + msg_pub = Float64() + msg_pub.data = self.diff + self.pid_state.publish(msg_pub) + + def pub_timer_callback(self): + self.desired_heading += math.pi / 2 + self.desired_heading %= 2 * math.pi + msg_pub = Float64() + msg_pub.data = 0.0 + self.get_logger().info('New angle setpoint: "%f"' % self.desired_heading) + self.pid_setpoint.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