示例#1
0
文件: prm.py 项目: veds12/gennav
    def plan(self, start, goal, env):
        """Constructs a graph avoiding obstacles and then plans path from start to goal within the graph.
        Args:
            start (gennav.utils.RobotState): tuple with start point coordinates.
            goal (gennav.utils.RobotState): tuple with end point coordinates.
            env (gennav.envs.Environment): Base class for an envrionment.
        Returns:
            gennav.utils.Trajectory: The planned path as trajectory
            dict: Dictionary containing additional information
        """
        # Check if start and goal states are obstacle free
        if not env.get_status(start):
            raise InvalidStartState(start,
                                    message="Start state is in obstacle.")

        if not env.get_status(goal):
            raise InvalidGoalState(goal, message="Goal state is in obstacle.")
        # construct graph
        graph = self.construct(env)
        # find collision free point in graph closest to start_point
        min_dist = float("inf")
        for node in graph.nodes:
            dist = compute_distance(node.position, start.position)
            traj = Trajectory([node, start])
            if dist < min_dist and (env.get_traj_status(traj)):
                min_dist = dist
                s = node
        # find collision free point in graph closest to end_point
        min_dist = float("inf")
        for node in graph.nodes:
            dist = compute_distance(node.position, goal.position)
            traj = Trajectory([node, goal])
            if dist < min_dist and (env.get_traj_status(traj)):
                min_dist = dist
                e = node
        # add start_point to path
        path = [start]
        traj = Trajectory(path)
        # perform astar search
        p = astar(graph, s, e)
        if len(p.path) == 1:
            raise PathNotFound(p, message="Path contains only one state")
        else:
            traj.path.extend(p.path)
        # add end_point to path
        traj.path.append(goal)
        return traj, {}
示例#2
0
    def plan(self, start, goal, env):
        """Plans the path to be taken by the robot to get from start to goal in the form of waypoints

        Args:
            start (gennav.utils.RobotState) : starting state of the robot (x, y and z coordinates)
            goal (gennav.utils.RobotState) : goal state of the robot (x, y and z coordinates)
            env (gennav.envs.Environment) : Type of environment the robot is operating in

        Returns:
            trajectory (gennav.utils.Trajectory) : A list of waypoints(in the form of robot states) that the robot will follow to go to the goal from the start
            dict: Dictionary containing additional information
        """
        # Check if start and goal states are obstacle free
        if not env.get_status(start):
            raise InvalidStartState(start,
                                    message="Start state is in obstacle.")

        if not env.get_status(goal):
            raise InvalidGoalState(goal, message="Goal state is in obstacle.")

        self.current = start
        self.goal = goal
        self.env = env
        waypoints = [self.current]
        while (math.sqrt((self.current.position.x - self.goal.position.x)**2 +
                         (self.current.position.y - self.goal.position.y)**2) >
               self.error):
            grad_attract = self.grad_attractive()
            grad_repel = self.grad_repulsive()
            grad = [0, 0]
            grad[0] = grad_attract[0] + grad_repel[0]
            grad[1] = grad_attract[1] + grad_repel[1]
            self.current.position.x = self.current.position.x - self.STEP_SIZE * grad[
                0]
            self.current.position.y = self.current.position.y - self.STEP_SIZE * grad[
                1]
            waypoints.append(self.current)
            trajectory = Trajectory(waypoints)
        if len(trajectory.path) == 1:
            raise PathNotFound(trajectory,
                               message="Path contains only one state")
        return trajectory, {}
示例#3
0
    def plan(self, start, goal, env):
        """Path planning method

        Args:
            start (gennav.utils.common.RobotState): Starting state.
            goal (gennav.utils.common.RobotState): Destination state
            env (gennav.envs.Environment): Environment object

        Returns:
            gennav.utils.Trajectory: The path as a Trajectory
            dict: Dictionary containing additional information like the node_list
        """
        # Check if start and goal states are obstacle free
        if not env.get_status(start):
            raise InvalidStartState(start,
                                    message="Start state is in obstacle.")

        if not env.get_status(goal):
            raise InvalidGoalState(goal, message="Goal state is in obstacle.")
        # Initialize start and goal nodes.
        x_start = Node(state=start)
        x_goal = Node(state=goal)
        # Starting the tree:
        node_list = [x_start]

        # X_soln contains all the nodes near the goal
        X_soln = []

        for i in range(self.max_iter):
            # defining the best cost as cbest
            if len(X_soln) == 0:
                cbest = float("inf")
            else:
                cbest = X_soln[0].cost + compute_distance(
                    X_soln[0].state.position, x_goal.state.position)
                for node in X_soln:
                    if (node.cost + compute_distance(node.state.position,
                                                     x_goal.state.position) <
                            cbest):
                        cbest = node.cost + compute_distance(
                            node.state.position, x_goal.state.position)
            # sample the new random point using the sample function
            if cbest < float("inf"):
                # Converting x_start and x_goal into arrays so that matrix calculations can be handled
                x_start_array = np.array(
                    [x_start.state.position.x, x_start.state.position.y],
                    dtype=np.float32,
                ).reshape(2, 1)

                x_goal_array = np.array(
                    [x_goal.state.position.x, x_goal.state.position.y],
                    dtype=np.float32).reshape(2, 1)

                cmin = np.linalg.norm((x_goal_array - x_start_array))

                x_center = (x_start_array + x_goal_array) / 2

                a1 = (x_goal_array - x_start_array) / cmin
                I1 = np.eye(len(x_start_array))[0].reshape(
                    len(x_start_array), 1)

                M = np.dot(a1, I1.T)

                [u, s, v] = np.linalg.svd(M)

                # numpy returns the transposed value for v, so to convert it back
                v = v.T

                # Calculating the rotation to world frame matrix given by C = U*diag{1,....1.det(U)det(V)}*V.T where * denotes matrix multiplication
                diag = np.eye(2)
                diag[1, 1] = np.linalg.det(u) * np.linalg.det(v)
                C = np.dot(np.dot(u, diag), v.T)

                L = np.eye(2)
                L[0, 0] = cbest / 2
                L[1, 1] = np.sqrt(cbest**2 - cmin**2) / 2

                rand_state = self.circular_sampler()
                x_ball = np.array(
                    [rand_state.position.x, rand_state.position.y],
                    dtype=np.float32).reshape(2, 1)

                x_rand_array = np.dot(np.dot(C, L), x_ball) + x_center
                x_rand = RobotState()
                x_rand.position.x = x_rand_array[0, 0]
                x_rand.position.y = x_rand_array[1, 0]

                x_rand_node = Node(state=x_rand)

            else:
                x_rand = self.rectangular_sampler()
                x_rand_node = Node(state=x_rand)

            # Finding the nearest node to the random point
            distance_list = [
                compute_distance(node.state.position,
                                 x_rand_node.state.position)
                for node in node_list
            ]

            min_dist = distance_list[0]
            min_index = 0

            for index, distance in enumerate(distance_list):
                if distance < min_dist:
                    min_dist = distance
                    min_index = index

            x_nearest = node_list[min_index]

            # Steering at a distance of self.expand_dis

            theta = compute_angle(x_nearest.state.position,
                                  x_rand_node.state.position)

            x = x_nearest.state.position.x + self.expand_dis * math.cos(theta)
            y = x_nearest.state.position.y + self.expand_dis * math.sin(theta)
            t = RobotState(position=Point(x, y))

            x_new = Node(state=t)
            # Defining a temporary trajectory between the new node and its nearest node
            traj = Trajectory(path=[x_nearest.state, x_new.state])
            # Checking whether new node and the nearest node can be connected
            if env.get_traj_status(traj):
                # Adding new node to the node list
                node_list.append(x_new)

                # Defining the neighbours of x_new
                X_near = []
                for node in node_list:
                    if (compute_distance(
                            node.state.position, x_new.state.position)) < (
                                self.neighbourhood_radius
                            ) and (  # If it is inside the neighbourhood radius
                                compute_distance(node.state.position,
                                                 x_new.state.position) != 0):
                        X_near.append(node)

                x_min = x_nearest
                c_min = x_min.cost + self.expand_dis

                for x_near in X_near:
                    c_new = x_near.cost + compute_distance(
                        x_near.state.position, x_new.state.position)

                    if c_new < c_min:
                        traj = Trajectory(path=[x_near.state, x_new.state])

                        if env.get_traj_status(traj):
                            x_min = x_near
                            c_min = c_new

                # Defining the parent node and cost of x_new
                x_new.parent = x_min
                x_new.cost = c_min

                # Rewiring
                for x_near in X_near:
                    c_near = x_near.cost
                    c_new = x_new.cost + compute_distance(
                        x_near.state.position, x_new.state.position)

                    if c_new < c_near:
                        traj = Trajectory(path=[x_new.state, x_near.state])

                        if env.get_traj_status(traj):
                            x_near.parent = x_new
                            x_near.cost = c_new

                goal_traj = Trajectory(path=[x_new.state, x_goal.state])

                if (compute_distance(x_goal.state.position,
                                     x_new.state.position)
                    ) < self.goal_distance and env.get_traj_status(goal_traj):
                    X_soln.append(x_new)

        # X_soln contains all the solutions
        if len(X_soln) == 0:
            print("No solution found!")
            path = []
            path.append(x_start.state)
            traj = Trajectory(path=path)
            info_dict = {}
            info_dict["node_list"] = node_list
            if len(traj.path) == 1:
                raise PathNotFound(path,
                                   message="Path contains only one state")
            return (traj, info_dict)

        else:
            print("Goal reached!")
            Cbest = X_soln[0].cost
            Xbest = X_soln[0]
            node_list.append(x_goal)

            for node in X_soln:
                if node.cost < Cbest:
                    Cbest = node.cost
                    Xbest = node

            x_goal.parent = Xbest

            # Xbest is the optimum solution to the problem.

            # Back tracing the path:
            path = []
            path.append(x_goal.state)
            path.append(Xbest.state)
            p = Xbest.parent

            while p is not None:
                path.append(p.state)
                p = p.parent

            path.append(x_start.state)
            path.reverse()

            # print("No. of solutions " + str(len(X_soln)))

            trajectory = Trajectory(path=path)
            info_dict = {}
            info_dict["node_list"] = node_list

            return (trajectory, info_dict)
示例#4
0
文件: rrg.py 项目: veds12/gennav
    def plan(self, start, end, env):
        """Plans path from start to goal avoiding obstacles.
        Args:
            start (gennav.utils.RobotState): Starting state
            end (gennav.utils.RobotState): Goal state
            env: (gennav.envs.Environment) Base class for an envrionment.
        Returns:
            gennav.utils.Trajectory: The planned path as trajectory
            dict: Dictionary containing additional information
        """
        # Check if start and end states are obstacle free
        if not env.get_status(start):
            raise InvalidStartState(start,
                                    message="Start state is in obstacle.")

        if not env.get_status(end):
            raise InvalidGoalState(end, message="Goal state is in obstacle.")

        # Initialize graph
        graph = Graph()
        graph.add_node(start)

        # Initialize node list with Starting Position
        node_list = [start]

        # Loop for maximum iterations to get the best possible path
        for iter in range(self.max_iter):

            rnd_node = self.sampler()

            # Find nearest node to the sampled point

            distance_list = [
                compute_distance(node.position, rnd_node.position)
                for node in node_list
            ]

            try:
                # for python2
                nearest_node_index = min(xrange(len(distance_list)),
                                         key=distance_list.__getitem__)
            except NameError:
                # for python 3
                nearest_node_index = distance_list.index(min(distance_list))
            nearest_node = node_list[nearest_node_index]

            # Create new point in the direction of sampled point

            theta = math.atan2(
                rnd_node.position.y - nearest_node.position.y,
                rnd_node.position.x - nearest_node.position.x,
            )

            new_node = RobotState(position=Point(
                nearest_node.position.x + self.exp_dis * math.cos(theta),
                nearest_node.position.y + self.exp_dis * math.sin(theta),
            ))
            # Check whether new point is inside an obstacles
            trj = Trajectory([nearest_node, new_node])
            if not env.get_status(new_node) or not env.get_traj_status(trj):
                continue
            else:
                node_list.append(new_node)

            # FINDING NEAREST INDICES
            nnode = len(node_list) + 1
            # The circle in which to check parent node and rewiring
            r = self.circle * math.sqrt((math.log(nnode) / nnode))
            dist_list = [
                compute_distance(node.position, new_node.position)
                for node in node_list
            ]
            # Getting all the indexes within r units of new_node
            near_inds = [dist_list.index(i) for i in dist_list if i <= r**2]
            graph.add_node(new_node)
            graph.add_edge(nearest_node, new_node)
            # Add all the collision free edges to the graph.
            for ind in near_inds:
                node_check = node_list[ind]
                trj = Trajectory([new_node, node_check])
                # If the above condition is met append the edge.
                if env.get_traj_status(trj):
                    graph.add_edge(new_node, node_check)
        if end not in graph.nodes:
            min_cost = 2.0
            closest_node = RobotState()
            for node in graph.nodes:
                temp = compute_distance(node.position, end.position)
                if env.get_traj_status(Trajectory([node, end
                                                   ])) and temp < min_cost:
                    min_cost = temp
                    closest_node = node
            graph.add_edge(closest_node, end)
            graph.add_node(end)
        if start in graph.edges[end]:
            graph.del_edge(start, end)

        path = []
        p = astar(graph, start, end)
        path.extend(p.path)
        if len(path) != 1:
            print("Goal Reached!")
        path = Trajectory(path)

        if len(path.path) == 1:
            raise PathNotFound(path, message="Path contains only one state")

        return path, {}
示例#5
0
文件: rrtstar.py 项目: veds12/gennav
    def plan(self, start, goal, env):
        """Path planning method

        Args:
            start (gennav.utils.common.RobotState): Starting state.
            goal (gennav.utils.common.RobotState): Destination state
            env (gennav.envs.Environment): Environment object

        Returns:
            gennav.utils.Trajectory: The path as a Trajectory
            dict: Dictionary containing additional information like the node_list
        """
        # Check if start and goal states are obstacle free
        if not env.get_status(start):
            raise InvalidStartState(start, message="Start state is in obstacle.")

        if not env.get_status(goal):
            raise InvalidGoalState(goal, message="Goal state is in obstacle.")
        # Initialize start and goal nodes.
        x_start = Node(state=start)
        x_goal = Node(state=goal)
        # Starting the tree:
        node_list = [x_start]

        # X_soln contains all the nodes near the goal
        X_soln = []

        for i in range(self.max_iter):
            # defining the best cost as cbest
            if len(X_soln) == 0:
                cbest = float("inf")
            else:
                cbest = X_soln[0].cost + compute_distance(
                    X_soln[0].state.position, x_goal.state.position
                )
                for node in X_soln:
                    if (
                        node.cost
                        + compute_distance(node.state.position, x_goal.state.position)
                        < cbest
                    ):
                        cbest = node.cost + compute_distance(
                            node.state.position, x_goal.state.position
                        )
            # sample the new random point using the sample function
            x_rand = self.rectangular_sampler()
            x_rand_node = Node(state=x_rand)

            # Finding the nearest node to the random point
            distance_list = [
                compute_distance(node.state.position, x_rand_node.state.position)
                for node in node_list
            ]

            min_dist = distance_list[0]
            min_index = 0

            for index, distance in enumerate(distance_list):
                if distance < min_dist:
                    min_dist = distance
                    min_index = index

            x_nearest = node_list[min_index]

            # Steering at a distance of self.expand_dis

            theta = compute_angle(x_nearest.state.position, x_rand_node.state.position)

            x = x_nearest.state.position.x + self.expand_dis * math.cos(theta)
            y = x_nearest.state.position.y + self.expand_dis * math.sin(theta)
            t = RobotState(position=Point(x, y))

            x_new = Node(state=t)
            # Defining a temporary trajectory between the new node and its nearest node
            traj = Trajectory(path=[x_nearest.state, x_new.state])
            # Checking whether new node and the nearest node can be connected
            if env.get_traj_status(traj):
                # Adding new node to the node list
                node_list.append(x_new)

                # Defining the neighbours of x_new
                X_near = []
                for node in node_list:
                    if (compute_distance(node.state.position, x_new.state.position)) < (
                        self.neighbourhood_radius
                    ) and (  # If it is inside the neighbourhood radius
                        compute_distance(node.state.position, x_new.state.position) != 0
                    ):
                        X_near.append(node)

                x_min = x_nearest
                c_min = x_min.cost + self.expand_dis

                for x_near in X_near:
                    c_new = x_near.cost + compute_distance(
                        x_near.state.position, x_new.state.position
                    )

                    if c_new < c_min:
                        traj = Trajectory(path=[x_near.state, x_new.state])

                        if env.get_traj_status(traj):
                            x_min = x_near
                            c_min = c_new

                # Defining the parent node and cost of x_new
                x_new.parent = x_min
                x_new.cost = c_min

                # Rewiring
                for x_near in X_near:
                    c_near = x_near.cost
                    c_new = x_new.cost + compute_distance(
                        x_near.state.position, x_new.state.position
                    )

                    if c_new < c_near:
                        traj = Trajectory(path=[x_new.state, x_near.state])

                        if env.get_traj_status(traj):
                            x_near.parent = x_new
                            x_near.cost = c_new

                goal_traj = Trajectory(path=[x_new.state, x_goal.state])

                if (
                    compute_distance(x_goal.state.position, x_new.state.position)
                ) < self.goal_distance and env.get_traj_status(goal_traj):
                    X_soln.append(x_new)

        # X_soln contains all the solutions
        if len(X_soln) == 0:
            print("No solution found!")
            path = []
            path.append(x_start.state)
            traj = Trajectory(path=path)
            info_dict = {}
            info_dict["node_list"] = node_list
            if len(traj.path) == 1:
                raise PathNotFound(path, message="Path contains only one state")
            return (traj, info_dict)

        else:
            print("Goal reached!")
            Cbest = X_soln[0].cost
            Xbest = X_soln[0]
            node_list.append(x_goal)

            for node in X_soln:
                if node.cost < Cbest:
                    Cbest = node.cost
                    Xbest = node

            x_goal.parent = Xbest

            # Xbest is the optimum solution to the problem.

            # Back tracing the path:
            path = []
            path.append(x_goal.state)
            path.append(Xbest.state)
            p = Xbest.parent

            while p is not None:
                path.append(p.state)
                p = p.parent

            path.append(x_start.state)
            path.reverse()

            # print("No. of solutions " + str(len(X_soln)))

            trajectory = Trajectory(path=path)
            info_dict = {}
            info_dict["node_list"] = node_list

            return (trajectory, info_dict)
示例#6
0
文件: rrt.py 项目: archit2604/gennav
    def plan(self, start, goal, env):
        """Plans path from start to goal avoiding obstacles.

        Args:
            start_point(gennav.utils.RobotState): with start point coordinates.
            end_point (gennav.utils.RobotState): with end point coordinates.
            env: (gennav.envs.Environment) Base class for an envrionment.

        Returns:
            gennav.utils.Trajectory: The planned path as trajectory
            dict: Dictionary containing additional information like the node_list
        """
        # Check if start and goal states are obstacle free
        if not env.get_status(start):
            raise InvalidStartState(start,
                                    message="Start state is in obstacle.")

        if not env.get_status(goal):
            raise InvalidGoalState(goal, message="Goal state is in obstacle.")

        # Initialize start and goal nodes
        start_node = Node(state=start)
        goal_node = Node(state=goal)

        # Initialize node_list with start
        node_list = [start_node]

        # Loop to keep expanding the tree towards goal if there is no direct connection
        traj = Trajectory(path=[start, goal])
        if not env.get_traj_status(traj):
            while True:
                # Sample random state in specified area
                rnd_state = self.sampler()

                # Find nearest node to the sampled point
                distance_list = [
                    compute_distance(node.state.position, rnd_state.position)
                    for node in node_list
                ]
                try:
                    # for python2
                    nearest_node_index = min(xrange(len(distance_list)),
                                             key=distance_list.__getitem__)
                except NameError:
                    # for python 3
                    nearest_node_index = distance_list.index(
                        min(distance_list))

                nearest_node = node_list[nearest_node_index]

                # Create new point in the direction of sampled point
                theta = math.atan2(
                    rnd_state.position.y - nearest_node.state.position.y,
                    rnd_state.position.x - nearest_node.state.position.x,
                )
                new_point = Point()
                new_point.x = (nearest_node.state.position.x +
                               self.expand_dis * math.cos(theta))
                new_point.y = (nearest_node.state.position.y +
                               self.expand_dis * math.sin(theta))

                # Check whether new point is inside an obstacles
                if not env.get_status(RobotState(position=new_point)):
                    continue
                else:
                    new_node = Node.from_coordinates(new_point)
                    new_node.parent = nearest_node
                    node_list.append(new_node)

                # Check if goal has been reached or if there is direct connection to goal
                distance_to_goal = compute_distance(goal_node.state.position,
                                                    new_node.state.position)

                traj = Trajectory(path=[RobotState(position=new_point), goal])
                if distance_to_goal < self.expand_dis or env.get_traj_status(
                        traj):
                    goal_node.parent = node_list[-1]
                    node_list.append(goal_node)
                    print("Goal reached!")
                    break

        else:
            goal_node.parent = start_node
            node_list = [start_node, goal_node]

        # Construct path by traversing backwards through the tree
        path = []
        last_node = node_list[-1]
        while last_node.parent is not None:
            path.append(last_node.state)
            last_node = last_node.parent
        path.append(start)
        info_dict = {}
        info_dict["node_list"] = node_list
        path = Trajectory(path[::-1])

        if len(path.path) == 1:
            raise PathNotFound(path, message="Path contains only one state")

        return (path, info_dict)