vector_magnitude = point_to_test.find_distance_between_points(point_goal)
    attraction_vector = Point(point_goal.x - point_to_test.x, point_goal.y - point_to_test.y)
    attraction_vector.scale_point(ATTRACTION_COEFFICIENT / vector_magnitude)
    return attraction_vector


def repulsive_force(point_to_test, point_obstacle, polygon_centroid):
    distance_to_obstacle = point_to_test.find_distance_between_points(point_obstacle)
    distance_to_center = point_to_test.find_distance_between_points(polygon_centroid)
    repulsive_vector = Point(0, 0)
    abs_distance = distance_to_center - distance_to_obstacle
    if distance_to_center <= REPULSIVE_RANGE:
        repulsive_magnitude = (0.5*REPULSIVE_COEFFICIENT)*(1/(distance_to_center-3)**2)
        # *(1/abs_distance**2)
        vector_magnitude = point_to_test.find_distance_between_points(polygon_centroid)
        repulsive_vector.set_x((point_to_test.x - polygon_centroid.x) * repulsive_magnitude / vector_magnitude)
        repulsive_vector.set_y((point_to_test.y - polygon_centroid.y) * repulsive_magnitude / vector_magnitude)

    return repulsive_vector


def total_potential_force(att_vector, rep_vector):
    total_vector = Point(att_vector.x + rep_vector.x, att_vector.y + att_vector.y)
    return total_vector


def potential_get_path(polygon, point_start, point_goal, polygon_centroid):
    path = [Point(point_start.x, point_start.y)]
    point_current = Point(point_start.x, point_start.y)
    step = 0
    while point_current.find_distance_between_points(point_goal) >= TARGET_RANGE and step <= TOTAL_STEP: