Ejemplo n.º 1
0
    def choose_best_nodes(self, map_info):
        # Since path planning takes a lot of time for many nodes we should reduce the possible result to the nodes
        # with the best distance and topological costs.
        if self.method == 'cost_based_fallback':
            yield self.closer_node(map_info), None, None
            return

        nodes = list(self.cluster_nodes(map_info.nodes, map_info.robot_px, self.cost_based_properties['node_clusters']))
        topo_costs = [self._topological_cost(node, map_info.ogm) for node in nodes]
        best_nodes_idx = self.weight_costs(
            topo_costs,
            [euclidean(node, map_info.robot_px) for node in nodes]
        ).argsort()[::-1]  # We need descending order since we now want to maximize.

        count = 0
        for idx in best_nodes_idx:
            node = nodes[idx]
            path = map_info.create_path(node)
            if path:
                count += 1
                yield node, path, topo_costs[idx]
            if count == self.cost_based_properties['max_paths']:
                break
        if count == 0:
            Print.art_print("Failed to create any path. Falling back to closer unoccupied.", Print.RED)
            self.method = 'cost_based_fallback'
            yield self.closer_node(map_info), None, None
Ejemplo n.º 2
0
 def normalize_costs(costs):
     """
     :rtype: numpy.ndarray
     """
     Print.art_print("Costs before normalization:\n" + str(costs), Print.BLUE)
     assert (costs >= 0).all()
     return 1 - (costs.transpose() / numpy.abs(costs).max(axis=1)).transpose()
Ejemplo n.º 3
0
    def checkTarget(self, event):
        # Check if we have a target or if the robot just wanders
        if not self.inner_target_exists or not self.move_with_target or self.next_subtarget == len(
                self.subtargets):
            return

        self.counter_to_next_sub -= 1
        if self.counter_to_next_sub == 0:
            Print.art_print('\n~~~~ Time reset ~~~~', Print.RED)
            self.inner_target_exists = False
            self.target_exists = False
            self.force_random = True
            return

        # Get the robot pose in pixels
        [rx, ry] = [
            self.robot_perception.robot_pose['x_px'] -
            self.robot_perception.origin['x'] /
            self.robot_perception.resolution,
            self.robot_perception.robot_pose['y_px'] -
            self.robot_perception.origin['y'] /
            self.robot_perception.resolution
        ]
        ######################### NOTE: QUESTION  ##############################
        # What if a later subtarget or the end has been reached before the next subtarget? Alter the code
        # accordingly. Check if distance is less than 7 px (14 cm). Slice the list of subtargets and then reverse it.
        for idx, st in enumerate(self.subtargets[self.next_subtarget::][::-1]):
            # Right now, idx refers to the sliced & reversed array, fix it.
            idx = len(self.subtargets) - 1 - idx
            assert idx >= self.next_subtarget
            dist = math.hypot(rx - st[0], ry - st[1])
            if dist < 7:
                self.next_subtarget = idx + 1
                self.counter_to_next_sub = self.count_limit
                if self.next_subtarget == len(self.subtargets):
                    self.target_exists = False
                break
        ########################################################################
        # Publish the current target
        if self.next_subtarget == len(self.subtargets):
            return

        subtarget = [
            self.subtargets[self.next_subtarget][0] *
            self.robot_perception.resolution +
            self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1] *
            self.robot_perception.resolution +
            self.robot_perception.origin['y']
        ]
        RvizHandler.printMarker(
            [subtarget],
            1,  # Type: Arrow
            0,  # Action: Add
            "map",  # Frame
            "art_next_subtarget",  # Namespace
            [0, 0, 0.8, 0.8],  # Color RGBA
            0.2  # Scale
        )
Ejemplo n.º 4
0
    def checkTarget(self, event):

        # Check if we have a target or if the robot just wanders
        if not self.inner_target_exists or not self.move_with_target or self.next_subtarget == len(
                self.subtargets):
            return

        # Check if timer has expired
        if self.timer_flag:
            if self.timerThread.expired:
                Print.art_print('\n~~~~ Time reset ~~~~', Print.RED)
                self.inner_target_exists = False
                self.target_exists = False
                return

        # Get the robot pose in pixels
        [rx, ry] = [
            self.robot_perception.robot_pose['x_px'] -
            self.robot_perception.origin['x'] /
            self.robot_perception.resolution,
            self.robot_perception.robot_pose['y_px'] -
            self.robot_perception.origin['y'] /
            self.robot_perception.resolution
        ]
        theta_robot = self.robot_perception.robot_pose['th']

        # Clear achieved targets
        self.subtargets = self.subtargets[self.next_subtarget:]
        self.next_subtarget = 0

        # If distance between the robot pose and the next subtarget is < 7 pixel consider that Target is Reached
        dist = math.hypot(rx - self.subtargets[self.next_subtarget][0],
                          ry - self.subtargets[self.next_subtarget][1])
        if dist < 7:
            self.next_subtarget += 1
            self.counter_to_next_sub = self.count_limit
            # Check if the final subtarget has been approached
            if self.next_subtarget == len(self.subtargets):
                self.target_exists = False

        # Publish the current target
        if self.next_subtarget >= len(self.subtargets):
            return

        subtarget = [
            self.subtargets[self.next_subtarget][0] *
            self.robot_perception.resolution +
            self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1] *
            self.robot_perception.resolution +
            self.robot_perception.origin['y']
        ]

        RvizHandler.printMarker([subtarget], 1, 0, "map", "art_next_subtarget",
                                [0, 0, 0.8, 0.8], 0.2)
Ejemplo n.º 5
0
    def cluster_nodes(nodes_original, robot_px, n_clusters):
        Print.art_print("Trying to cluster:" + str(nodes_original), Print.BLUE)
        whitened = whiten(nodes_original)
        _, cluster_idx = kmeans2(whitened, n_clusters)
        Print.art_print("Ended with clusters:" + str(cluster_idx), Print.BLUE)

        keyfun = lambda x: cluster_idx[x[0]]
        nodes = sorted(enumerate(nodes_original), key=keyfun)
        for _, group in itertools.groupby(nodes, key=keyfun):
            # For each cluster pick the farthest one.
            max_idx = max(group, key=lambda x: euclidean(robot_px, x[1]))[0]
            yield nodes_original[max_idx]
 def selectFurthestTarget(self, ogm, coverage, brushogm, ogm_limits, nodes):
     # The next target in pixels
     tinit = time.time()
     next_target = [0, 0]
     for i in range(len(nodes) - 1, 0, -1):
         x = nodes[i][0]
         y = nodes[i][1]
         if  ogm[x][y] < 50 and coverage[x][y] < 50 and \
           brushogm[x][y] > 10:
             next_target = [x, y]
             Print.art_print("Select furthest target time: " + str(time.time() - tinit), \
                 Print.ORANGE)
             return next_target
     return self.selectRandomTarget(ogm, coverage, brushogm, ogm_limits)
Ejemplo n.º 7
0
 def selectRandomTarget(self, ogm, coverage, brushogm, ogm_limits):
     # The next target in pixels
     tinit = time.time()
     next_target = [0, 0]
     found = False
     while not found:
         x_rand = random.randint(0, ogm.shape[0] - 1)
         y_rand = random.randint(0, ogm.shape[1] - 1)
         if ogm[x_rand][y_rand] < 50 and coverage[x_rand][y_rand] < 50 and \
             brushogm[x_rand][y_rand] > 5:
             next_target = [x_rand, y_rand]
             found = True
     Print.art_print("Select random target time: " + str(time.time() - tinit), \
         Print.ORANGE)
     return next_target
Ejemplo n.º 8
0
 def TargetSel(self, ogm, coverage, brushogm, ogm_limits):
     tinit = time.time()
     next_target = [0, 0]
     a = []
     for x in range(0, ogm.shape[0]):
         for y in range(0, ogm.shape[1]):
             temp = (brushogm[x][y] - 5) * 0.6 + (ogm[x][y] - 50) * 0.2 + (
                 coverage[x][y] - 50) * 0.2
             a.append(temp)
     c = a.index(min(a))
     if ogm.shape[0] >= ogm.shape[1]:
         next_target = [c % ogm.shape[0], c / ogm.shape[0]]
     else:
         next_target = [c / ogm.shape[0], c % ogm.shape[0]]
     Print.art_print("Select  target time: " + str(time.time() - tinit), \
                Print.ORANGE)
     return next_target
    def selectNearestTopologyNode(self, robot_pose, resolution, nodes):
        # The next target in pixels
        tinit = time.time()
        next_target = [0, 0]
        w_dist = 10000
        x_g, y_g = 500, 500
        sigma = 100
        g_robot_pose = self.robot_perception.getGlobalCoordinates(
            [robot_pose['x_px'], robot_pose['y_px']])  # can I use that?
        for node in nodes:
            # print resolution
            self.path = self.path_planning.createPath(
                g_robot_pose, node, resolution)  # can I use that?
            if len(self.path) == 0:
                break
            x_n, y_n = node[0], node[1]
            exp = ((x_n - x_g)**2 + (y_n - y_g)**2) / (2 * (sigma**2))
            scale_factor = 1 / (1 - math.exp(-exp) + 0.01)

            coords = zip(
                *self.path)  # dist is [[x1 x2 x3..],[y1 y2 y3 ..]] #transpose

            coord_shift = np.empty_like(coords)
            coord_shift[0] = coords[0][-1:] + coords[0][:-1]  # (xpi+1)
            coord_shift[1] = coords[1][-1:] + coords[1][:-1]  # (ypi+1)

            coords = np.asarray(coords)

            dist = [
                (a - b)**2 for a, b in zip(coords[:, 1:], coord_shift[:, 1:])
            ]  # (xpi - xpi+1)^2 , (ypi-ypi+1)^2
            dist = sum(np.sqrt(dist[0] + dist[1]))

            w = dist * (1 / scale_factor)
            if w < w_dist and len(self.path) != 0:
                if self.prev_target == node:
                    break
                w_dist = w
                next_target = node

        self.prev_target = next_target  # dont select the same target it we failed already

        Print.art_print(
            "Select nearest node target time: " + str(time.time() - tinit),
            Print.ORANGE)
        return next_target
Ejemplo n.º 10
0
    def select_by_cost(self, map_info):
        nodes, paths, topo_costs = zip(*self.choose_best_nodes(map_info))
        if nodes[0] is None:  # choose_best_node's yield when no path is found will make nodes = (None,)
            return -1, -1
        elif len(nodes) == 1:
            return nodes[0]

        best_path_idx = self.weight_costs(
            topo_costs,
            [self.distance_cost(path, map_info.robot_px) for path in paths],  # Distance
            [self.coverage_cost(path, map_info.coverage) for path in paths],  # Coverage
            [self.rotation_cost(path, map_info.robot_px, map_info.theta) for path in paths]  # Rotational
        ).argmax()
        assert paths[best_path_idx]
        target = nodes[best_path_idx]

        Print.art_print("Best: {}".format(best_path_idx), Print.BLUE)
        return target
Ejemplo n.º 11
0
 def topological_cost(node, ogm, threshold):
     result = 0
     for dir_x, dir_y in [(0, 1), (1, 1), (1, 0), (1, -1), (0, -1), (-1, -1), (-1, 0), (-1, 1)]:
         cost = 0
         idx = 0
         x, y = node
         while cost < threshold:
             idx += 1
             x_c = x + idx * dir_x
             y_c = y + idx * dir_y
             cost = (x - x_c) ** 2 + (y - y_c) ** 2
             if ogm[x_c][y_c] > 50:
                 break
             elif ogm[x_c][y_c] in [50, -1]:
                 Print.art_print("{},{} is unknown!".format(x_c, y_c), Print.RED)
                 cost = threshold
                 break
         result += min(threshold, cost)
     return result
    def MINTargetSel(self, ogm, coverage, brushogm, ogm_limits, nodes, x, y):
        tinit = time.time()
        next_target = [0, 0]
        a = []
        b = []
        d = []
        print(x)
        print(y)
        for n in nodes:
            #The min distance topo node from robot
            temp = -(math.pow(x - n[0], 2) + math.pow(y - n[1], 2))
            a.append(temp)
            b.append(n[0])
            d.append(n[1])

        c = a.index(max(a))
        next_target = [b[c], d[c]]

        Print.art_print("Select MIN target time: " + str(time.time() - tinit), \
                Print.ORANGE)
        print(next_target)
        return next_target
Ejemplo n.º 13
0
    def selectTarget(self, init_ogm, coverage, robot_pose, origin,
                     resolution, force_random=False):

        target = [-1, -1]

        ######################### NOTE: QUESTION  ##############################
        # Implement a smart way to select the next target. You have the 
        # following tools: ogm_limits, Brushfire field, OGM skeleton,
        # topological nodes.

        # Find only the useful boundaries of OGM. Only there calculations
        # have meaning
        ogm_limits = OgmOperations.findUsefulBoundaries(init_ogm, origin, resolution)

        # Blur the OGM to erase discontinuities due to laser rays
        ogm = OgmOperations.blurUnoccupiedOgm(init_ogm, ogm_limits)

        # Calculate Brushfire field
        tinit = time.time()
        brush = self.brush.obstaclesBrushfireCffi(ogm, ogm_limits)
        Print.art_print("Brush time: " + str(time.time() - tinit), Print.ORANGE)

        # Calculate skeletonization
        tinit = time.time()
        skeleton = self.topo.skeletonizationCffi(ogm,
                                                 origin, resolution, ogm_limits)
        Print.art_print("Skeletonization time: " + str(time.time() - tinit), Print.ORANGE)

        # Find topological graph
        tinit = time.time()
        nodes = self.topo.topologicalNodes(ogm, skeleton, coverage, origin,
                                           resolution, brush, ogm_limits)
        Print.art_print("Topo nodes time: " + str(time.time() - tinit), Print.ORANGE)

        # Visualization of topological nodes
        vis_nodes = []
        for n in nodes:
            vis_nodes.append([
                n[0] * resolution + origin['x'],
                n[1] * resolution + origin['y']
            ])
        RvizHandler.printMarker(
            vis_nodes,
            1,  # Type: Arrow
            0,  # Action: Add
            "map",  # Frame
            "art_topological_nodes",  # Namespace
            [0.3, 0.4, 0.7, 0.5],  # Color RGBA
            0.1  # Scale
        )

        # Random point
        if self.method == 'random' or force_random == True:
            target = self.selectRandomTarget(ogm, coverage, brush, ogm_limits)
        ########################################################################

        return target
Ejemplo n.º 14
0
    def createPath(self, robot_pose, target_pose, resolution):

        # Ask for path
        resp = OgmppPathPlanningSrvResponse()
        req = OgmppPathPlanningSrvRequest()
        req.data.begin = Point()
        req.data.end = Point()

        req.data.begin.x = robot_pose[0] * resolution
        req.data.begin.y = robot_pose[1] * resolution
        req.data.end.x = target_pose[0] * resolution
        req.data.end.y = target_pose[1] * resolution
        req.method = "uniform_prm"

        tinit = time.time()
        resp = self.ogmpp_pp(req)
        Print.art_print("Path planning time: " + str(time.time() - tinit), Print.ORANGE)

        path = []
        for p in resp.path.poses:
            path.append([p.pose.position.x / resolution,
                p.pose.position.y / resolution])

        return path
Ejemplo n.º 15
0
    def selectTarget(self):
        # IMPORTANT: The robot must be stopped if you call this function until
        # it is over
        # Check if we have a map
        while not self.robot_perception.have_map:
            Print.art_print("Navigation: No map yet", Print.RED)
            return

        print "\nClearing all markers"
        RvizHandler.printMarker(
            [[0, 0]],
            1,  # Type: Arrow
            3,  # Action: delete all
            "map",  # Frame
            "null",  # Namespace
            [0, 0, 0, 0],  # Color RGBA
            0.1  # Scale
        )

        print '\n\n----------------------------------------------------------'
        print "Navigation: Producing new target"
        # We are good to continue the exploration
        # Make this true in order not to call it again from the speeds assignment
        self.target_exists = True

        # Gets copies of the map and coverage
        local_ogm = self.robot_perception.getMap()
        local_ros_ogm = self.robot_perception.getRosMap()
        local_coverage = self.robot_perception.getCoverage()
        print "Got the map and Coverage"
        self.path_planning.setMap(local_ros_ogm)

        # Once the target has been found, find the path to it
        # Get the global robot pose
        # Get robot pose in global (map's) coordinates
        rp_l_px = [
            self.robot_perception.robot_pose['x_px'],
            self.robot_perception.robot_pose['y_px']
        ]
        rp_g_px = self.robot_perception.toGlobalCoordinates(
            rp_l_px, with_resolution=True)
        g_robot_pose = rp_g_px

        # Call the target selection function to select the next best goal
        # Choose target function
        self.path = []
        force_random = False
        while len(self.path) == 0:
            start = time.time()
            target = self.target_selection.selectTarget(
                local_ogm, local_coverage, self.robot_perception.robot_pose,
                self.robot_perception.origin, self.robot_perception.resolution,
                force_random)

            self.path = self.path_planning.createPath(
                g_robot_pose, target, self.robot_perception.resolution)
            print "Navigation: Path for target found with " + str(len(self.path)) + \
                  " points"
            if len(self.path) == 0:
                Print.art_print(
                    "Path planning failed. Fallback to random target selection",
                    Print.RED)
                force_random = True

        # Reverse the path to start from the robot
        self.path = self.path[::-1]

        # Break the path to sub-goals every 2 pixels (1m = 20px)
        step = 1
        n_subgoals = int(len(self.path) / step)
        self.subtargets = []
        for i in range(0, n_subgoals):
            self.subtargets.append(self.path[i * step])
        self.subtargets.append(self.path[-1])
        self.next_subtarget = 0
        print "The path produced " + str(len(self.subtargets)) + " subgoals"

        ######################### NOTE: QUESTION  ##############################
        # The path is produced by an A* algorithm. This means that it is
        # optimal in length but 1) not smooth and 2) length optimality
        # may not be desired for coverage-based exploration
        ########################################################################

        self.counter_to_next_sub = self.count_limit

        # Publish the path for visualization purposes
        ros_path = Path()
        ros_path.header.frame_id = "map"
        for p in self.path:
            ps = PoseStamped()
            ps.header.frame_id = "map"
            ######################### NOTE: QUESTION  ##############################
            # Fill the ps.pose.position values to show the path in RViz
            # You must understand what self.robot_perception.resolution
            # and self.robot_perception.origin are.

            # Convert p from pixel-units to meter
            p_m = self.robot_perception.toMeterUnits(p, False)

            # Convert p_m from global (map's) coordinates to relative (image's) coordinates (using resolution = 1)
            p_m_r = self.robot_perception.toRelativeCoordinates(p_m, False)

            # Fill in $ps object
            ps.pose.position.x = p_m_r[0]
            ps.pose.position.y = p_m_r[1]
            ########################################################################
            ros_path.poses.append(ps)
        self.path_publisher.publish(ros_path)

        # Publish the subtargets for visualization purposes
        subtargets_mark = []
        for s in self.subtargets:
            st_m = self.robot_perception.toMeterUnits(s, False)
            st_m_r = self.robot_perception.toRelativeCoordinates(st_m, False)
            subtargets_mark.append(st_m_r)

        RvizHandler.printMarker(
            subtargets_mark,
            2,  # Type: Sphere
            0,  # Action: Add
            "map",  # Frame
            "art_subtargets",  # Namespace
            [0, 0.8, 0.0, 0.8],  # Color RGBA
            0.2  # Scale
        )

        self.inner_target_exists = True
    def checkTarget(self, event):
        # Check if we have a target or if the robot just wanders
        if self.inner_target_exists == False or self.move_with_target == False or \
                        self.next_subtarget == len(self.subtargets):
            return

        self.counter_to_next_sub -= 1

        if self.counter_to_next_sub == 0:
            Print.art_print('\n~~~~ Time reset ~~~~', Print.RED)
            self.inner_target_exists = False
            self.target_exists = False
            return

        # Get the robot pose in pixels
        [rx, ry] = [
            self.robot_perception.robot_pose['x_px'] -
            self.robot_perception.origin['x'] /
            self.robot_perception.resolution,
            self.robot_perception.robot_pose['y_px'] -
            self.robot_perception.origin['y'] /
            self.robot_perception.resolution
        ]

        # # Find the distance between the robot pose and the next subtarget
        # dist = math.hypot(
        #     rx - self.subtargets[self.next_subtarget][0],
        #     ry - self.subtargets[self.next_subtarget][1])

        ######################### NOTE: QUESTION  ##############################
        # What if a later subtarget or the end has been reached before the
        # next subtarget? Alter the code accordingly.
        # Check if distance is less than 7 px (14 cm)
        # if dist < 5:
        #     self.next_subtarget += 1
        #     self.counter_to_next_sub = self.count_limit
        #     # Check if the final subtarget has been approached
        #     if self.next_subtarget == len(self.subtargets):
        #         self.target_exists = False

        # find the distance between robot and ALL subtargets
        dists = (math.hypot(rx - self.subtargets[subtarget][0],
                            ry - self.subtargets[subtarget][1])
                 for subtarget, _ in enumerate(self.subtargets))

        # check the distance of each subtarget from the robot
        # go towards the nearest and change index of next_subtarget
        # accordingly
        for idx, dist in enumerate(dists):
            if dist < 5:
                self.next_subtarget = idx + 1
                self.counter_to_next_sub = self.count_limit
                # Check if the final subtarget has been approached
                if self.next_subtarget == len(self.subtargets):
                    self.target_exists = False
        ########################################################################

        # Publish the current target
        if self.next_subtarget == len(self.subtargets):
            return

        subtarget = [
            self.subtargets[self.next_subtarget][0] *
            self.robot_perception.resolution +
            self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1] *
            self.robot_perception.resolution +
            self.robot_perception.origin['y']
        ]

        RvizHandler.printMarker(
            [subtarget],
            1,  # Type: Arrow
            0,  # Action: Add
            "map",  # Frame
            "art_next_subtarget",  # Namespace
            [0, 0, 0.8, 0.8],  # Color RGBA
            0.2  # Scale
        )
    def selectTarget(self, ogm, coverage, robot_pose, origin, \
        resolution, force_random = False):

        # Random point
        if self.method == 'random' or force_random == True:

            init_ogm = ogm

            # Find only the useful boundaries of OGM. Only there calculations
            # have meaning
            ogm_limits = OgmOperations.findUsefulBoundaries(
                init_ogm, origin, resolution)

            # Blur the OGM to erase discontinuities due to laser rays
            ogm = OgmOperations.blurUnoccupiedOgm(init_ogm, ogm_limits)

            # Calculate Brushfire field
            tinit = time.time()
            brush = self.brush.obstaclesBrushfireCffi(ogm, ogm_limits)
            Print.art_print("Brush time: " + str(time.time() - tinit),
                            Print.ORANGE)

            # Calculate skeletonization
            tinit = time.time()
            skeleton = self.topo.skeletonizationCffi(ogm, \
                       origin, resolution, ogm_limits)
            Print.art_print(
                "Skeletonization time: " + str(time.time() - tinit),
                Print.ORANGE)

            # Find topological graph
            tinit = time.time()
            nodes = self.topo.topologicalNodes(ogm, skeleton, coverage, origin, \
                    resolution, brush, ogm_limits)
            Print.art_print("Topo nodes time: " + str(time.time() - tinit),
                            Print.ORANGE)

            # Visualization of topological nodes
            vis_nodes = []
            for n in nodes:
                vis_nodes.append([
                    n[0] * resolution + origin['x'],
                    n[1] * resolution + origin['y']
                ])
            RvizHandler.printMarker(\
                vis_nodes,\
                1, # Type: Arrow
                0, # Action: Add
                "map", # Frame
                "art_topological_nodes", # Namespace
                [0.3, 0.4, 0.7, 0.5], # Color RGBA
                0.1 # Scale
            )

            target = self.selectRandomTarget(ogm, coverage, brush, ogm_limits)
            return [False, target]

        tinit = time.time()

        g_robot_pose = [robot_pose['x_px'] - int(origin['x'] / resolution), \
                        robot_pose['y_px'] - int(origin['y'] / resolution)]

        # Calculate coverage frontier with sobel filters
        tinit = time.time()
        cov_dx = scipy.ndimage.sobel(coverage, 0)
        cov_dy = scipy.ndimage.sobel(coverage, 1)
        cov_frontier = np.hypot(cov_dx, cov_dy)
        cov_frontier *= 100 / np.max(cov_frontier)
        cov_frontier = 100 * (cov_frontier > 80)
        Print.art_print("Sobel filters time: " + str(time.time() - tinit),
                        Print.BLUE)

        # Remove the edges that correspond to obstacles instead of frontiers (in a 5x5 radius)
        kern = 5
        tinit = time.time()
        i_rng = np.matlib.repmat(
            np.arange(-(kern / 2), kern / 2 + 1).reshape(kern, 1), 1, kern)
        j_rng = np.matlib.repmat(np.arange(-(kern / 2), kern / 2 + 1), kern, 1)
        for i in range((kern / 2), cov_frontier.shape[0] - (kern / 2)):
            for j in range((kern / 2), cov_frontier.shape[1] - (kern / 2)):
                if cov_frontier[i, j] == 100:
                    if np.any(ogm[i + i_rng, j + j_rng] > 99):
                        cov_frontier[i, j] = 0
        Print.art_print("Frontier trimming time: " + str(time.time() - tinit),
                        Print.BLUE)

        # Save coverage frontier as image (for debugging purposes)
        # scipy.misc.imsave('test.png', np.rot90(cov_frontier))

        # Frontier detection/grouping
        tinit = time.time()
        labeled_frontiers, num_frontiers = scipy.ndimage.label(
            cov_frontier, np.ones((3, 3)))
        Print.art_print("Frontier grouping time: " + str(time.time() - tinit),
                        Print.BLUE)

        goals = np.full((num_frontiers, 2), -1)
        w_dist = np.full(len(goals), -1)
        w_turn = np.full(len(goals), -1)
        w_size = np.full(len(goals), -1)
        w_obst = np.full(len(goals), -1)

        # Calculate the centroid and its cost, for each frontier
        for i in range(1, num_frontiers + 1):
            points = np.where(labeled_frontiers == i)

            # Discard small groupings (we chose 20 as a treshold arbitrarily)
            group_length = points[0].size
            if group_length < 20:
                labeled_frontiers[points] = 0
                continue
            sum_x = np.sum(points[0])
            sum_y = np.sum(points[1])
            centroid = np.array([sum_x / group_length,
                                 sum_y / group_length]).reshape(2, 1)

            # Find the point on the frontier nearest (2-norm) to the centroid, and use it as goal
            nearest_idx = np.linalg.norm(np.array(points) - centroid,
                                         axis=0).argmin()
            print ogm[int(points[0][nearest_idx]), int(points[1][nearest_idx])]
            goals[i - 1, :] = np.array(
                [points[0][nearest_idx], points[1][nearest_idx]])

            # Save centroids for later visualisation (for debugging purposes)
            labeled_frontiers[int(goals[i - 1, 0]) + i_rng,
                              int(goals[i - 1, 1]) + j_rng] = i

            # Calculate size of obstacles between robot and goal
            line_pxls = list(bresenham(int(goals[i-1,0]), int(goals[i-1,1]),\
                                       g_robot_pose[0], g_robot_pose[1]))

            ogm_line = list(map(lambda pxl: ogm[pxl[0], pxl[1]], line_pxls))

            N_occupied = len(list(filter(lambda x: x > 25, ogm_line)))
            N_line = len(line_pxls)
            w_obst[i - 1] = float(N_occupied) / N_line
            # print('Occupied  = '+str(N_occupied))
            # print('Full Line = '+str(N_line))
            # ipdb.set_trace()

            # Manhattan distance
            w_dist[i - 1] = scipy.spatial.distance.cityblock(
                goals[i - 1, :], g_robot_pose)

            # Missalignment
            theta = np.arctan2(goals[i - 1, 1] - g_robot_pose[1],
                               goals[i - 1, 0] - g_robot_pose[0])
            w_turn[i - 1] = (theta - robot_pose['th'])
            if w_turn[i - 1] > np.pi:
                w_turn[i - 1] -= 2 * np.pi
            elif w_turn[i - 1] < -np.pi:
                w_turn[i - 1] += 2 * np.pi
            # We don't care about the missalignment direction so we abs() it
            w_turn[i - 1] = np.abs(w_turn[i - 1])

            # Frontier size
            w_size[i - 1] = group_length

        # Save frontier groupings as an image (for debugging purposes)
        cmap = plt.cm.jet
        norm = plt.Normalize(vmin=labeled_frontiers.min(),
                             vmax=labeled_frontiers.max())
        image = cmap(norm(labeled_frontiers))
        plt.imsave('frontiers.png', np.rot90(image))

        # Remove invalid goals and weights
        valids = w_dist != -1
        goals = goals[valids]
        w_dist = w_dist[valids]
        w_turn = w_turn[valids]
        w_size = w_size[valids]
        w_obst = w_obst[valids]

        # Normalize weights
        w_dist = (w_dist - min(w_dist)) / (max(w_dist) - min(w_dist))
        w_turn = (w_turn - min(w_turn)) / (max(w_turn) - min(w_turn))
        w_size = (w_size - min(w_size)) / (max(w_size) - min(w_size))

        # Cancel turn weight for frontiers that have obstacles
        w_turn[np.where(w_obst != 0)] = 1

        # Goal cost function
        c_dist = 3
        c_turn = 2
        c_size = 1
        c_obst = 4
        costs = c_dist * w_dist + c_turn * w_turn + c_size * w_size + c_obst * w_obst

        min_idx = costs.argmin()

        Print.art_print("Target selection time: " + str(time.time() - tinit),
                        Print.ORANGE)
        print costs
        print goals

        ## Safety Distance from obstacles
        # Goal Coordinates
        grid_size = 20
        [found_obstacle, closest_obstacle,
         min_dist] = self.detectObstacles(grid_size, ogm, goals[min_idx])

        if found_obstacle == False:
            return [False, goals[min_idx]]

        # Calculate new goal:
        dist_from_obstacles = 10
        normal_vector = goals[min_idx] - closest_obstacle
        normal_vector = normal_vector / np.hypot(normal_vector[0],
                                                 normal_vector[1])
        new_goal = closest_obstacle + dist_from_obstacles * normal_vector

        # Check new goal for nearby obstacles
        [found_obstacle, closest_obstacle, min_dist_new] = \
            self.detectObstacles(grid_size, ogm, new_goal.round())

        # Return
        if min_dist < 7:
            # return the target with max min_dist
            if min_dist_new > min_dist:
                return [True, new_goal.round(), goals[min_idx]]
            else:
                return [False, goals[min_idx]]
        else:
            return [False, goals[min_idx]]
    def selectTarget(self):
        # IMPORTANT: The robot must be stopped if you call this function until
        # it is over
        # Check if we have a map
        while self.robot_perception.have_map == False:
          Print.art_print("Navigation: No map yet", Print.RED)
          return

        print "\nClearing all markers"
        RvizHandler.printMarker(\
            [[0, 0]],\
            1, # Type: Arrow
            3, # Action: delete all
            "map", # Frame
            "null", # Namespace
            [0,0,0,0], # Color RGBA
            0.1 # Scale
        )

        print '\n\n----------------------------------------------------------'
        print "Navigation: Producing new target"
        # We are good to continue the exploration
        # Make this true in order not to call it again from the speeds assignment
        self.target_exists = True

        # Gets copies of the map and coverage
        local_ogm = self.robot_perception.getMap()
        local_ros_ogm = self.robot_perception.getRosMap()
        local_coverage = self.robot_perception.getCoverage()
        print "Got the map and Coverage"
        self.path_planning.setMap(local_ros_ogm)

        # Once the target has been found, find the path to it
        # Get the global robot pose
        g_robot_pose = self.robot_perception.getGlobalCoordinates(\
              [self.robot_perception.robot_pose['x_px'],\
              self.robot_perception.robot_pose['y_px']])

        # Call the target selection function to select the next best goal
        # Choose target function
        self.path = []
        force_random = False
        while len(self.path) == 0:
          start = time.time()
          target = self.target_selection.selectTarget(\
                    local_ogm,\
                    local_coverage,\
                    self.robot_perception.robot_pose,
                    self.robot_perception.origin,
                    self.robot_perception.resolution,
                    force_random)

          self.path = self.path_planning.createPath(\
              g_robot_pose,\
              target,
              self.robot_perception.resolution)
          print "Navigation: Path for target found with " + str(len(self.path)) +\
              " points"
          if len(self.path) == 0:
            Print.art_print(\
                "Path planning failed. Fallback to random target selection", \
                Print.RED)
            force_random = True

        # Reverse the path to start from the robot
        self.path = self.path[::-1]

        #########################################
        # Extra challenge #1
        # A. Smooth path planner
        if len(self.path) > 3:
            x = np.array(self.path)
            y = np.copy(x)
            a = 0.5
            b = 0.1

            # FORMULA : y_i = y_i + a * (x_i - y_i) + b * (y_i+1 - 2 * y_i + y_i+1)

            epsilon = np.sum(np.abs(a * (x[1:-1, :] - y[1:-1, :]) + b * (y[2:, :] - 2*y[1:-1, :] + y[:-2, :])))
            while epsilon > 1e-3:
                y[1:-1, :] += a * (x[1:-1, :] - y[1:-1, :]) + b * (y[2:, :] - 2*y[1:-1, :] + y[:-2, :])
                epsilon = np.sum(np.abs(a * (x[1:-1, :] - y[1:-1, :]) + b * (y[2:, :] - 2*y[1:-1, :] + y[:-2, :])))

            # Copy the smoother path
            self.path = y.tolist()

        # Break the path to subgoals every 2 pixels (1m = 20px)
        step = 1
        n_subgoals = (int) (len(self.path)/step)
        self.subtargets = []
        for i in range(0, n_subgoals):
          self.subtargets.append(self.path[i * step])
        self.subtargets.append(self.path[-1])
        self.next_subtarget = 0
        print "The path produced " + str(len(self.subtargets)) + " subgoals"

        ######################### NOTE: QUESTION  ##############################
        # The path is produced by an A* algorithm. This means that it is
        # optimal in length but 1) not smooth and 2) length optimality
        # may not be desired for coverage-based exploration
        ########################################################################


        self.counter_to_next_sub = self.count_limit

        # Publish the path for visualization purposes
        ros_path = Path()
        ros_path.header.frame_id = "map"
        for p in self.path:
          ps = PoseStamped()
          ps.header.frame_id = "map"
          ps.pose.position.x = 0
          ps.pose.position.y = 0
          ######################### NOTE: QUESTION  ##############################
          # Fill the ps.pose.position values to show the path in RViz
          # You must understand what self.robot_perception.resolution
          # and self.robot_perception.origin are.
          ps.pose.position.x = p[0] * self.robot_perception.resolution + self.robot_perception.origin['x']
          ps.pose.position.y = p[1] * self.robot_perception.resolution + self.robot_perception.origin['y']
          ########################################################################
          ros_path.poses.append(ps)
        self.path_publisher.publish(ros_path)

        # Publish the subtargets for visualization purposes
        subtargets_mark = []
        for s in self.subtargets:
          subt = [
            s[0] * self.robot_perception.resolution + \
                    self.robot_perception.origin['x'],
            s[1] * self.robot_perception.resolution + \
                    self.robot_perception.origin['y']
            ]
          subtargets_mark.append(subt)

        RvizHandler.printMarker(\
            subtargets_mark,\
            2, # Type: Sphere
            0, # Action: Add
            "map", # Frame
            "art_subtargets", # Namespace
            [0, 0.8, 0.0, 0.8], # Color RGBA
            0.2 # Scale
        )

        self.inner_target_exists = True
    def checkTarget(self, event):
        # Check if we have a target or if the robot just wanders
        if self.inner_target_exists == False or self.move_with_target == False or\
                self.next_subtarget == len(self.subtargets):
            return

        self.counter_to_next_sub -= 1

        if self.counter_to_next_sub == 0:
            Print.art_print('\n~~~~ Time reset ~~~~', Print.RED)
            self.inner_target_exists = False
            self.target_exists = False
            return

        # Get the robot pose in pixels
        [rx, ry] = [\
            self.robot_perception.robot_pose['x_px'] - \
                    self.robot_perception.origin['x'] / self.robot_perception.resolution,\
            self.robot_perception.robot_pose['y_px'] - \
                    self.robot_perception.origin['y'] / self.robot_perception.resolution\
                    ]

        # Find the distance between the robot pose and the next subtarget
        dist = math.hypot(\
            rx - self.subtargets[self.next_subtarget][0], \
            ry - self.subtargets[self.next_subtarget][1])

        ######################### NOTE: QUESTION  ##############################
        # What if a later subtarget or the end has been reached before the
        # next subtarget? Alter the code accordingly.

        # If the robot is in the starting point it immediately sets the next subtarget
        if self.next_subtarget == 0:
            self.next_subtarget += 1
            self.counter_to_next_sub = self.count_limit
        else:
            # Check if there is a later subtarget, closer than the next one
            # If one is found, make it the next subtarget and update the time
            for i in range(self.next_subtarget + 1, len(self.subtargets) - 1):
                # Find the distance between the robot pose and the later subtarget
                dist_from_later = math.hypot(\
                    rx - self.subtargets[i][0], \
                    ry - self.subtargets[i][1])
                if dist_from_later < 15:
                    self.next_subtarget = i
                    self.counter_to_next_sub = self.count_limit + 100
                    dist = dist_from_later
                    break

            # If distance from subtarget is less than 5, go to the next one
            if dist < 5:
                self.next_subtarget += 1
                self.counter_to_next_sub = self.count_limit
                # Check if the final subtarget has been approached
                if self.next_subtarget == len(self.subtargets):
                    self.target_exists = False
        ########################################################################

        # Publish the current target
        if self.next_subtarget == len(self.subtargets):
            return

        subtarget = [\
            self.subtargets[self.next_subtarget][0]\
                * self.robot_perception.resolution + \
                self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1]\
                * self.robot_perception.resolution + \
                self.robot_perception.origin['y']\
            ]

        RvizHandler.printMarker(\
            [subtarget],\
            1, # Type: Arrow
            0, # Action: Add
            "map", # Frame
            "art_next_subtarget", # Namespace
            [0, 0, 0.8, 0.8], # Color RGBA
            0.2 # Scale
        )
    def selectTarget(self):
        # IMPORTANT: The robot must be stopped if you call this function until
        # it is over
        # Check if we have a map
        while self.robot_perception.have_map == False:
            Print.art_print("Navigation: No map yet", Print.RED)
            return

        print "\nClearing all markers"
        RvizHandler.printMarker(\
            [[0, 0]],\
            1, # Type: Arrow
            3, # Action: delete all
            "map", # Frame
            "null", # Namespace
            [0,0,0,0], # Color RGBA
            0.1 # Scale
        )

        print '\n\n----------------------------------------------------------'
        print "Navigation: Producing new target"
        # We are good to continue the exploration
        # Make this true in order not to call it again from the speeds assignment
        self.target_exists = True

        # Gets copies of the map and coverage
        local_ogm = self.robot_perception.getMap()
        local_ros_ogm = self.robot_perception.getRosMap()
        local_coverage = self.robot_perception.getCoverage()
        print "Got the map and Coverage"
        self.path_planning.setMap(local_ros_ogm)

        # Once the target has been found, find the path to it
        # Get the global robot pose
        g_robot_pose = self.robot_perception.getGlobalCoordinates(\
              [self.robot_perception.robot_pose['x_px'],\
              self.robot_perception.robot_pose['y_px']])

        # Call the target selection function to select the next best goal
        # Choose target function
        self.path = []
        force_random = False
        while len(self.path) == 0:
            start = time.time()
            target = self.target_selection.selectTarget(\
                      local_ogm,\
                      local_coverage,\
                      self.robot_perception.robot_pose,
                      self.robot_perception.origin,
                      self.robot_perception.resolution,
                      force_random)

            self.path = self.path_planning.createPath(\
                g_robot_pose,\
                target,
                self.robot_perception.resolution)
            print "Navigation: Path for target found with " + str(len(self.path)) +\
                " points"
            if len(self.path) == 0:
                Print.art_print(\
                    "Path planning failed. Fallback to random target selection", \
                    Print.RED)
                force_random = True

        # Reverse the path to start from the robot
        self.path = self.path[::-1]

        ######################### NOTE: QUESTION  ##############################
        # The path is produced by an A* algorithm. This means that it is
        # optimal in length but 1) not smooth and 2) length optimality
        # may not be desired for coverage-based exploration

        weight_data = 0.5  # How much weight to update the data (a)
        weight_smooth = 0.1  # How much weight to smooth the coordinates (b)
        min_change = 0.0001  # Minimum change per iteration to keep iterating
        new_path = np.copy(np.array(self.path))
        path_length = len(self.path[0])
        change = min_change

        while change >= min_change:
            change = 0.0
            for i in range(1, len(new_path) - 1):
                for j in range(path_length):
                    # Initialize x, y
                    x_i = self.path[i][j]
                    y_i = new_path[i][j]
                    y_prev = new_path[i - 1][j]
                    y_next = new_path[i + 1][j]

                    y_i_saved = y_i

                    # Minimize the distance between coordinates of the original
                    # path (y) and the smoothed path (x). Also minimize the
                    # difference between the coordinates of the smoothed path
                    # at time step i, and neighboring time steps. In order to do
                    # all the minimizations, we use Gradient Ascent.
                    y_i += weight_data * (x_i - y_i) + weight_smooth * (
                        y_next + y_prev - (2 * y_i))
                    new_path[i][j] = y_i

                    change += abs(y_i - y_i_saved)

        self.path = new_path
        ########################################################################

        # Break the path to subgoals every 2 pixels (1m = 20px)
        step = 1
        n_subgoals = (int)(len(self.path) / step)
        self.subtargets = []
        for i in range(0, n_subgoals):
            self.subtargets.append(self.path[i * step])
        self.subtargets.append(self.path[-1])
        self.next_subtarget = 0
        print "The path produced " + str(len(self.subtargets)) + " subgoals"

        self.counter_to_next_sub = self.count_limit

        # Publish the path for visualization purposes
        ros_path = Path()
        ros_path.header.frame_id = "map"
        for p in self.path:
            ps = PoseStamped()
            ps.header.frame_id = "map"
            ps.pose.position.x = 0
            ps.pose.position.y = 0
            ######################### NOTE: QUESTION  ##############################
            # Fill the ps.pose.position values to show the path in RViz
            # You must understand what self.robot_perception.resolution
            # and self.robot_perception.origin are.

            # Multiply subgoal's coordinates with resolution and
            # add robot.origin in order to translate between the (0,0) of the robot
            # pose and (0,0) of the map
            ps.pose.position.x = p[0] * self.robot_perception.resolution + \
                     self.robot_perception.origin['x']
            ps.pose.position.y = p[1] * self.robot_perception.resolution + \
                     self.robot_perception.origin['y']
            ########################################################################
            ros_path.poses.append(ps)
        self.path_publisher.publish(ros_path)

        # Publish the subtargets for visualization purposes
        subtargets_mark = []
        for s in self.subtargets:
            subt = [
              s[0] * self.robot_perception.resolution + \
                      self.robot_perception.origin['x'],
              s[1] * self.robot_perception.resolution + \
                      self.robot_perception.origin['y']
              ]
            subtargets_mark.append(subt)

        RvizHandler.printMarker(\
            subtargets_mark,\
            2, # Type: Sphere
            0, # Action: Add
            "map", # Frame
            "art_subtargets", # Namespace
            [0, 0.8, 0.0, 0.8], # Color RGBA
            0.2 # Scale
        )

        self.inner_target_exists = True
Ejemplo n.º 21
0
    def checkTarget(self, event):
        """
        Check if target/sub-target reached.
        :param event:
        :return:
        """
        if self.previous_next_subtarget is None or self.previous_next_subtarget < self.next_subtarget:
            Print.art_print("next_subtarget = %d" % self.next_subtarget,
                            Print.ORANGE)
            self.previous_next_subtarget = self.next_subtarget

        # Check if we have a target or if the robot just wanders
        if self.inner_target_exists == False \
                or self.move_with_target == False \
                or self.next_subtarget == len(self.subtargets):
            return

        self.counter_to_next_sub -= 1

        if self.counter_to_next_sub == 0:
            Print.art_print('\n~~~~ Time reset ~~~~', Print.RED)
            self.inner_target_exists = False
            self.target_exists = False
            return

        # Get the robot pose in: pixel units & global (map's) coordinate system
        rp_l_px = [
            self.robot_perception.robot_pose['x_px'],
            self.robot_perception.robot_pose['y_px']
        ]
        # rp_g_px = self.robot_perception.toGlobalCoordinates(rp_l_px)
        [rx, ry] = [
            self.robot_perception.robot_pose['x_px'] -
            self.robot_perception.origin['x'] /
            self.robot_perception.resolution,
            self.robot_perception.robot_pose['y_px'] -
            self.robot_perception.origin['y'] /
            self.robot_perception.resolution
        ]
        rp_g_px = [rx, ry]

        # Find the distance between the robot pose and the next subtarget
        v_g_px = map(operator.sub, rp_g_px,
                     self.subtargets[self.next_subtarget])
        dist = math.hypot(v_g_px[0], v_g_px[1])

        ######################### NOTE: QUESTION  ##############################
        # What if a later subtarget or the end has been reached before the
        # next subtarget? Alter the code accordingly.
        # Check if distance is less than 7 px (14 cm)

        # if dist < 5:
        #     self.next_subtarget += 1
        #     self.counter_to_next_sub = self.count_limit
        #     # Check if the final subtarget has been approached
        #     if self.next_subtarget == len(self.subtargets):
        #         self.target_exists = False

        # Instead of checking only next sub-target check all remaining sub-targets (starting from end up to next
        # sub-target) and decide if robot is closer to another sub-target at later point in path
        for st_i in range(
                len(self.subtargets) - 1, self.next_subtarget - 1, -1):
            # @v_st_g_px: Difference of Global coordinates in Pixels between robot's position
            # and i-th" sub-target's position
            v_st_g_px = map(operator.sub, rp_g_px, self.subtargets[st_i])
            if math.hypot(v_st_g_px[0], v_st_g_px[1]) < 5:
                # reached @st_i, set next sub-target in path as robot's next sub-target
                self.next_subtarget = st_i + 1
                self.counter_to_next_sub = self.count_limit
                if self.next_subtarget == len(self.subtargets):
                    self.target_exists = False

        ########################################################################

        # Publish the current target
        if self.next_subtarget == len(self.subtargets):
            return

        subtarget = [
            self.subtargets[self.next_subtarget][0] *
            self.robot_perception.resolution +
            self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1] *
            self.robot_perception.resolution +
            self.robot_perception.origin['y']
        ]

        RvizHandler.printMarker(
            [subtarget],
            1,  # Type: Arrow
            0,  # Action: Add
            "map",  # Frame
            "art_next_subtarget",  # Namespace
            [0, 0, 0.8, 0.8],  # Color RGBA
            0.2  # Scale
        )
    def checkTarget(self, event):
        # Check if we have a target or if the robot just wanders
        if self.inner_target_exists == False or self.move_with_target == False or\
                self.next_subtarget == len(self.subtargets):
            return

        self.counter_to_next_sub -= 1

        if self.counter_to_next_sub == 0:
            Print.art_print('\n~~~~ Time reset ~~~~', Print.RED)
            self.inner_target_exists = False
            self.target_exists = False
            return

        # Get the robot pose in pixels
        [rx, ry] = [\
            self.robot_perception.robot_pose['x_px'] - \
                    self.robot_perception.origin['x'] / self.robot_perception.resolution,\
            self.robot_perception.robot_pose['y_px'] - \
                    self.robot_perception.origin['y'] / self.robot_perception.resolution\
                    ]
        for i in range(self.next_subtarget, len(self.subtargets)):
            # Find the distance between the robot pose and the next subtarget
            dist = math.hypot(\
                rx - self.subtargets[i][0], \
                ry - self.subtargets[i][1])

            ######################### NOTE: QUESTION  ##############################
            # What if a later subtarget or the end has been reached before the
            # next subtarget? Alter the code accordingly.
            # Check if distance is less than 7 px (14 cm)
            if dist < 7:
                self.next_subtarget = 1 + i
                self.counter_to_next_sub = self.count_limit
                # Check if the final subtarget has been approached
                if self.next_subtarget == len(self.subtargets):
                    self.target_exists = False

        ########################################################################

        # Publish the current target
        if self.next_subtarget == len(self.subtargets):
            return

        subtarget = [\
            self.subtargets[self.next_subtarget][0]\
                * self.robot_perception.resolution + \
                self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1]\
                * self.robot_perception.resolution + \
                self.robot_perception.origin['y']\
            ]

        RvizHandler.printMarker(\
            [subtarget],\
            1, # Type: Arrow
            0, # Action: Add
            "map", # Frame
            "art_next_subtarget", # Namespace
            [0, 0, 0.8, 0.8], # Color RGBA
            0.2 # Scale
        )
    def readMap(self, data):

        # OGM is a 2D array of size width x height
        # The values are from 0 to 100
        # 0 is an unoccupied pixel
        # 100 is an occupied pixel
        # 50 or -1 is the unknown

        # Locking the map
        self.map_compute = True

        self.ros_ogm = data
        # Reading the map pixels
        self.ogm_info = data.info

        if self.have_map == False or \
                self.ogm_info.width != self.prev_ogm_info.width or \
                self.ogm_info.height != self.prev_ogm_info.height:

            self.ogm = numpy.zeros((data.info.width, data.info.height), \
                    dtype = numpy.int)
            Print.art_print("Map & coverage expansion!", Print.GREEN)
            self.prev_ogm_info = self.ogm_info

            # Update coverage container as well
            coverage_copy = numpy.zeros(
                [self.ogm_info.width, self.ogm_info.height])
            print "Coverage copy new size: " + str(coverage_copy.shape)
            self.coverage_ogm.info = self.ogm_info
            self.coverage_ogm.data = \
                numpy.zeros(self.ogm_info.width * self.ogm_info.height)

            if self.have_map == True:
                print "Copying coverage field" + str(self.coverage.shape)
                for i in range(0, self.coverage.shape[0]):
                    for j in range(0, self.coverage.shape[1]):
                        coverage_copy[i][j] = self.coverage[i][j]

            # Coverage now gets the new size
            self.coverage = numpy.zeros(
                [self.ogm_info.width, self.ogm_info.height])
            for i in range(0, self.coverage.shape[0]):
                for j in range(0, self.coverage.shape[1]):
                    self.coverage[i][j] = coverage_copy[i][j]
            print "New coverage info: " + str(self.coverage.shape)

            for i in range(0, self.coverage.shape[0]):
                for j in range(0, self.coverage.shape[1]):
                    index = int(i + self.ogm_info.width * j)
                    self.coverage_ogm.data[index] = self.coverage[i][j]
                    # TODO: Thats not quite right - the origins must be checked

        for x in range(0, data.info.width):
            for y in range(0, data.info.height):
                self.ogm[x][y] = data.data[x + data.info.width * y]

        # Get the map's resolution - each pixel's side in meters
        self.resolution = data.info.resolution

        # Get the map's origin
        self.origin['x'] = data.info.origin.position.x
        self.origin['y'] = data.info.origin.position.y

        # Keep a copy
        self.ogm_copy = numpy.copy(self.ogm)

        # Update coverage
        x = self.robot_pose['x_px']
        y = self.robot_pose['y_px']
        xx = int(self.robot_pose['x_px'] +
                 abs(self.origin['x'] / self.resolution))
        yy = int(self.robot_pose['y_px'] +
                 abs(self.origin['y'] / self.resolution))
        for i in range(-20, 20):
            for j in range(-20, 20):
                if self.ogm[xx + i, yy + j] > 49 or self.ogm[xx + i,
                                                             yy + j] == -1:
                    continue
                self.coverage[xx + i, yy + j] = 100
                index = int((xx + i) + self.ogm_info.width * (yy + j))
                self.coverage_ogm.data[index] = 100
        self.coverage_publisher.publish(self.coverage_ogm)

        #NOTE: uncomment this to save coverage in image
        #scipy.misc.imsave('~/Desktop/test.png', self.coverage)

        # Unlock the map
        self.map_compute = False

        # If it is copied wait ...
        while self.map_token == True:
            pass

        # This is for the navigation
        if self.have_map == False:
            self.have_map = True
            Print.art_print("Robot perception: Map initialized", Print.GREEN)
Ejemplo n.º 24
0
    def selectTarget(self, ogm, coverage, robot_pose, origin, resolution, force_random=False):
        ######################### NOTE: QUESTION  ##############################
        # Implement a smart way to select the next target. You have the following tools: ogm_limits, Brushfire field,
        # OGM skeleton, topological nodes.

        # Find only the useful boundaries of OGM. Only there calculations have meaning.
        ogm_limits = OgmOperations.findUsefulBoundaries(ogm, origin, resolution)

        # Blur the OGM to erase discontinuities due to laser rays
        ogm = OgmOperations.blurUnoccupiedOgm(ogm, ogm_limits)

        # Calculate Brushfire field
        tinit = time.time()
        brush = self.brush.obstaclesBrushfireCffi(ogm, ogm_limits)
        Print.art_print("Brush time: " + str(time.time() - tinit), Print.ORANGE)

        # Calculate skeletonization
        tinit = time.time()
        skeleton = topology.skeletonizationCffi(ogm, origin, resolution, ogm_limits)
        Print.art_print("Skeletonization time: " + str(time.time() - tinit), Print.ORANGE)

        # Find topological graph
        tinit = time.time()
        nodes = topology.topologicalNodes(ogm, skeleton, coverage, brush)
        Print.art_print("Topo nodes time: " + str(time.time() - tinit), Print.ORANGE)

        # Visualization of topological nodes
        vis_nodes = [[n[0] * resolution + origin['x'], n[1] * resolution + origin['y']] for n in nodes]
        RvizHandler.printMarker(
            vis_nodes,
            1,  # Type: Arrow
            0,  # Action: Add
            "map",  # Frame
            "art_topological_nodes",  # Namespace
            [0.3, 0.4, 0.7, 0.5],  # Color RGBA
            0.1  # Scale
        )

        try:
            tinit = time.time()
        except:
            tinit = None
        if self.method == 'random' or force_random:
            target = self.selectRandomTarget(ogm, coverage, brush)
        elif self.method_is_cost_based():
            g_robot_pose = self.robot_perception.getGlobalCoordinates([robot_pose['x_px'], robot_pose['y_px']])
            self.path_planning.setMap(self.robot_perception.getRosMap())

            class MapContainer:
                def __init__(self):
                    self.skeleton = skeleton
                    self.coverage = coverage
                    self.ogm = ogm
                    self.brush = brush
                    self.nodes = [node for node in nodes if TargetSelection.is_good(brush, ogm, coverage, node)]
                    self.robot_px = [robot_pose['x_px'] - origin['x'] / resolution,
                                     robot_pose['y_px'] - origin['y'] / resolution]
                    self.theta = robot_pose['th']

                @staticmethod
                def create_path(path_target):
                    return self.path_planning.createPath(g_robot_pose, path_target, resolution)

            target = self.select_by_cost(MapContainer())
        else:
            assert False, "Invalid target_selector method."
        if tinit is not None:
            Print.art_print("Target method {} time: {}".format(self.method, time.time() - tinit), Print.ORANGE)
        return target
    def selectTarget(self, init_ogm, coverage, robot_pose, origin, \
        resolution, force_random = False):

        target = [-1, -1]

        ######################### NOTE: QUESTION  ##############################
        # Implement a smart way to select the next target. You have the
        # following tools: ogm_limits, Brushfire field, OGM skeleton,
        # topological nodes.

        # Find only the useful boundaries of OGM. Only there calculations
        # have meaning
        ogm_limits = OgmOperations.findUsefulBoundaries(
            init_ogm, origin, resolution)
        #print(ogm_limits)
        # Blur the OGM to erase discontinuities due to laser rays
        ogm = OgmOperations.blurUnoccupiedOgm(init_ogm, ogm_limits)

        # Calculate Brushfire field
        tinit = time.time()
        brush = self.brush.obstaclesBrushfireCffi(ogm, ogm_limits)
        Print.art_print("Brush time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Calculate skeletonization
        tinit = time.time()
        skeleton = self.topo.skeletonizationCffi(ogm, \
                   origin, resolution, ogm_limits)
        Print.art_print("Skeletonization time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Find topological graph
        tinit = time.time()
        nodes = self.topo.topologicalNodes(ogm, skeleton, coverage, origin, \
                resolution, brush, ogm_limits)
        Print.art_print("Topo nodes time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Visualization of topological nodes
        vis_nodes = []
        for n in nodes:
            vis_nodes.append([
                n[0] * resolution + origin['x'],
                n[1] * resolution + origin['y']
            ])
        RvizHandler.printMarker(\
            vis_nodes,\
            1, # Type: Arrow
            0, # Action: Add
            "map", # Frame
            "art_topological_nodes", # Namespace
            [0.3, 0.4, 0.7, 0.5], # Color RGBA
            0.1 # Scale
        )

        # Random point

        #if statement that makes the target selection random in case the remaining nodes are two
        if len(nodes) <= 2:
            target = self.selectRandomTarget(ogm, coverage, brush, ogm_limits)
            return target

        pose_global_x = int(robot_pose['x_px'] - origin['x'] / resolution)
        pose_global_y = int(robot_pose['y_px'] - origin['y'] / resolution)

        #the folowing variables receive the values read by the sonar sensor
        sonar_left = self.sonar.sonar_left_range
        sonar_right = self.sonar.sonar_right_range
        sonar_front = self.sonar.sonar_front_range

        #a total sum is calculated for the front,right and left sonar sensors
        sonar_sum = sonar_left + sonar_right + sonar_front
        numrows = ogm.shape[1]
        numcols = ogm.shape[0]

        #if statement used in case the robot is in a tight spot and determines the target in the direction there is maximum space
        if sonar_sum < 1.2:
            target = self.sonar_avoidance(pose_global_x, pose_global_y, ogm,
                                          numcols, numrows)
            return target

        #in case of a time out or a failure in path planning
        if self.method == 'random' or force_random == True:
            target = [
                self.node2_index_x, self.node2_index_y
            ]  #sets the current target as the previously calculated second best-scored target
            if self.timeout_happened == 1:
                target = self.sonar_avoidance(pose_global_x, pose_global_y,
                                              ogm, numcols, numrows)
                self.timeout_happened = 0
                return target
            self.timeout_happened = 1
            return target
        ########################################################################

        sum_min = 10000000
        dist_min = 10000000
        node_index_x = 0  #x value of the node with the lowest total cost
        node_index_y = 0  #y value of the node with the lowest total cost
        topo_cost = []  #list of topological costs for each node
        dist_cost = []  #list of distance costs for each node
        cov_cost = []  #list of coverage costs for each node

        #using the brushfire array in order to calculate topology cost for each node
        for n in nodes:
            sum_temp = 0
            index = n[1] + 1
            while brush[n[0], index] != 0:
                sum_temp += 1
                index += 1
                if index == numrows - 1:  #numrows
                    break
            index = n[1] - 1
            while brush[n[0], index] != 0:
                sum_temp += 1
                index -= 1
                if index == 0:
                    break
            index = n[0] + 1
            while brush[index, n[1]] != 0:
                sum_temp += 1
                index += 1
                if index == numcols - 1:  #numcols
                    break
            index = n[0] - 1
            while brush[index, n[1]] != 0:
                sum_temp += 1
                index -= 1
                if index == 0:
                    break

            topo_cost.append(sum_temp / 4)

        #using the coverage array in order to calculate coverage cost for each node
        numrows = len(coverage)
        numcols = len(coverage[0])
        for n in nodes:
            total_sum = 0
            sum_temp = 0
            index = n[1] + 1
            if index >= numrows or n[0] >= numcols:
                total_sum = 5000
                cov_cost.append(total_sum)
                continue
            while coverage[n[0], index] != 100:
                sum_temp += 1
                index += 1
                if index >= numcols - 1:  #numrows-1:
                    break
            total_sum += sum_temp * coverage[n[0], index] / 100
            index = n[1] - 1
            sum_temp = 0
            while coverage[n[0], index] != 100:
                sum_temp += 1
                index -= 1
                if index == 0:
                    break
            total_sum += sum_temp * coverage[n[0], index] / 100
            index = n[0] + 1
            sum_temp = 0
            if index >= numcols or n[1] >= numrows:
                total_sum = 5000
                cov_cost.append(total_sum)
                continue

            while coverage[index, n[1]] != 100:
                sum_temp += 1
                index += 1
                if index >= numrows - 1:  #numcols-1
                    break
            total_sum += sum_temp * coverage[index, n[1]] / 100
            index = n[0] - 1
            sum_temp = 0
            while coverage[index, n[1]] != 100:
                sum_temp += 1
                index -= 1
                if index == 0:
                    break
            total_sum += sum_temp * coverage[index, n[1]] / 100
            if total_sum == 0:
                total_sum = 5000
            cov_cost.append(total_sum)

            pose_global_x = int(robot_pose['x_px'] - origin['x'] / resolution)
            pose_global_y = int(robot_pose['y_px'] - origin['y'] / resolution)

            #eucledean distance between the robot pose and each node
            dist = math.sqrt(
                math.pow(pose_global_x - n[0], 2) +
                math.pow(pose_global_y - n[1], 2))
            dist_cost.append(dist)
        maxi = 0
        for i in range(0, len(cov_cost)):
            if cov_cost[i] != 5000 and cov_cost[i] > maxi:
                maxi = cov_cost[i]
        for i in range(0, len(cov_cost)):
            if cov_cost[i] == 5000:
                cov_cost[i] = maxi * 1.2

        #lists to store the normalized costs for each node
        topo_cost_norm = []
        dist_cost_norm = []
        cov_cost_norm = []
        final_cost = []
        min_final_cost = 1000000

        for i in range(0, len(dist_cost)):
            topo_cost_norm.append((np.float(topo_cost[i] - min(topo_cost)) /
                                   np.float(max(topo_cost) - min(topo_cost))))
            dist_cost_norm.append((dist_cost[i] - min(dist_cost)) /
                                  (max(dist_cost) - min(dist_cost)))
            if np.float(max(cov_cost) - min(cov_cost)) != 0:
                cov_cost_norm.append((np.float(cov_cost[i] - min(cov_cost)) /
                                      np.float(max(cov_cost) - min(cov_cost))))
            if max(cov_cost) != min(cov_cost):
                final_cost.append(
                    4 * topo_cost_norm[i] + 2 * dist_cost_norm[i] +
                    4 * cov_cost_norm[i]
                )  #optimal factor values in order to determine the best node to approach
            else:
                final_cost.append(
                    6 * topo_cost_norm[i] + 4 * dist_cost_norm[i]
                )  # exception if statement for the case coverage array cannot be used yet

            if (final_cost[i] < min_final_cost):
                min_final_cost = final_cost[i]
                self.node2_index_x = node_index_x  #storing the second best node to approach in case of path planning failure or time out
                self.node2_index_y = node_index_y  #
                node_index_x = nodes[i][0]
                node_index_y = nodes[i][1]

        target = [node_index_x, node_index_y]
        #in case current target is the same with the previous , sonar avoidance function is used to modify the robot pose
        if target == self.previous_target:
            target = self.sonar_avoidance(pose_global_x, pose_global_y, ogm,
                                          numcols, numrows)
        self.previous_target = target

        return target
Ejemplo n.º 26
0
    def selectTarget(self, init_ogm, coverage, robot_pose, origin, \
        resolution, force_random = False):

        target = [-1, -1]

        ######################### NOTE: QUESTION  ##############################
        # Implement a smart way to select the next target. You have the
        # following tools: ogm_limits, Brushfire field, OGM skeleton,
        # topological nodes.

        # Find only the useful boundaries of OGM. Only there calculations
        # have meaning
        ogm_limits = OgmOperations.findUsefulBoundaries(
            init_ogm, origin, resolution)

        # Blur the OGM to erase discontinuities due to laser rays
        ogm = OgmOperations.blurUnoccupiedOgm(init_ogm, ogm_limits)

        # Calculate Brushfire field
        tinit = time.time()
        brush = self.brush.obstaclesBrushfireCffi(ogm, ogm_limits)
        Print.art_print("Brush time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Calculate skeletonization
        tinit = time.time()
        skeleton = self.topo.skeletonizationCffi(ogm, \
                   origin, resolution, ogm_limits)
        Print.art_print("Skeletonization time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Find topological graph
        tinit = time.time()
        nodes = self.topo.topologicalNodes(ogm, skeleton, coverage, origin, \
                resolution, brush, ogm_limits)
        Print.art_print("Topo nodes time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Visualization of topological nodes
        vis_nodes = []
        for n in nodes:
            vis_nodes.append([
                n[0] * resolution + origin['x'],
                n[1] * resolution + origin['y']
            ])
        RvizHandler.printMarker(\
            vis_nodes,\
            1, # Type: Arrow
            0, # Action: Add
            "map", # Frame
            "art_topological_nodes", # Namespace
            [0.3, 0.4, 0.7, 0.5], # Color RGBA
            0.1 # Scale
        )

        # Check at autonomous_expl.yaml if target_selector = 'random' or 'smart'
        if self.method == 'random' or force_random == True:
            target = self.selectRandomTarget(ogm, coverage, brush, ogm_limits)
        elif self.method == 'smart' and force_random == False:
            tinit = time.time()
            # Get the robot pose in pixels
            [rx, ry] = [\
                robot_pose['x_px'] - \
                        origin['x'] / resolution,\
                robot_pose['y_px'] - \
                        origin['y'] / resolution\
                        ]
            g_robot_pose = [rx, ry]
            # If nodes > 25 the calculation time-cost is very big
            # In order to avoid time-reset we perform sampling on
            # the nodes list and take a half-sized sample
            for i in range(0, len(nodes)):
                nodes[i].append(i)
            if (len(nodes) > 25):
                nodes = random.sample(nodes, int(len(nodes) / 2))

            # Initialize weigths
            w_dist = [0] * len(nodes)
            w_rot = [robot_pose['th']] * len(nodes)
            w_cov = [0] * len(nodes)
            w_topo = [0] * len(nodes)
            # Calculate weights for every node in the topological graph
            for i in range(0, len(nodes)):
                # If path planning fails then give extreme values to weights
                path = self.path_planning.createPath(g_robot_pose, nodes[i],
                                                     resolution)
                if not path:
                    w_dist[i] = sys.maxsize
                    w_rot[i] = sys.maxsize
                    w_cov[i] = sys.maxsize
                    w_topo[i] = sys.maxsize
                else:
                    for j in range(1, len(path)):
                        # Distance cost
                        w_dist[i] += math.hypot(path[j][0] - path[j - 1][0],
                                                path[j][1] - path[j - 1][1])
                        # Rotational cost
                        w_rot[i] += abs(
                            math.atan2(path[j][0] - path[j - 1][0],
                                       path[j][1] - path[j - 1][1]))
                        # Coverage cost
                        w_cov[i] += coverage[int(path[j][0])][int(
                            path[j][1])] / (len(path))
                    # Add the coverage cost of 0-th node of the path
                    w_cov[i] += coverage[int(path[0][0])][int(
                        path[0][1])] / (len(path))
                    # Topological cost
                    # This metric depicts wether the target node
                    # is placed in open space or near an obstacle
                    # We want the metric to be reliable so we also check node's neighbour cells
                    w_topo[i] += brush[nodes[i][0]][nodes[i][1]]
                    w_topo[i] += brush[nodes[i][0] - 1][nodes[i][1]]
                    w_topo[i] += brush[nodes[i][0] + 1][nodes[i][1]]
                    w_topo[i] += brush[nodes[i][0]][nodes[i][-1]]
                    w_topo[i] += brush[nodes[i][0]][nodes[i][+1]]
                    w_topo[i] += brush[nodes[i][0] - 1][nodes[i][1] - 1]
                    w_topo[i] += brush[nodes[i][0] + 1][nodes[i][1] + 1]
                    w_topo[i] = w_topo[i] / 7

            # Normalize weights between 0-1
            for i in range(0, len(nodes)):
                w_dist[i] = 1 - (w_dist[i] - min(w_dist)) / (max(w_dist) -
                                                             min(w_dist))
                w_rot[i] = 1 - (w_rot[i] - min(w_rot)) / (max(w_rot) -
                                                          min(w_rot))
                w_cov[i] = 1 - (w_cov[i] - min(w_cov)) / (max(w_cov) -
                                                          min(w_cov))
                w_topo[i] = 1 - (w_topo[i] - min(w_topo)) / (max(w_topo) -
                                                             min(w_topo))

            # Set cost values
            # We set each cost's priority based on experimental results
            # from "Cost-Based Target Selection Techniques Towards Full Space
            # Exploration and Coverage for USAR Applications
            # in a Priori Unknown Environments" publication
            C1 = w_topo
            C2 = w_dist
            C3 = [1] * len(nodes)
            for i in range(0, len(nodes)):
                C3[i] -= w_cov[i]
            C4 = w_rot
            # Priority Weight
            C_PW = [0] * len(nodes)
            # Smoothing Factor
            C_SF = [0] * len(nodes)
            # Target's Final Priority
            C_FP = [0] * len(nodes)
            for i in range(0, len(nodes)):
                C_PW[i] = 2**3 * (1 - C1[i]) / .5 + 2**2 * (
                    1 - C2[i]) / .5 + 2**1 * (1 - C3[i]) / .5 + 2**0 * (
                        1 - C4[i]) / .5
                C_SF[i] = (2**3 * (1 - C1[i]) + 2**2 * (1 - C2[i]) + 2**1 *
                           (1 - C3[i]) + 2**0 * (1 - C4[i])) / (2**4 - 1)
                C_FP[i] = C_PW[i] * C_SF[i]

            # Select the node with the smallest C_FP value
            val, idx = min((val, idx) for (idx, val) in enumerate(C_FP))
            Print.art_print(
                "Select smart target time: " + str(time.time() - tinit),
                Print.BLUE)
            Print.art_print("Selected Target - Node: " + str(nodes[idx][2]),
                            Print.BLUE)
            target = nodes[idx]
        else:
            Print.art_print(
                "[ERROR] target_selector at autonomous_expl.yaml must be either 'random' or 'smart'",
                Print.RED)
        ########################################################################

        return target
    def __init__(self):

        # Flags for debugging and synchronization
        self.print_robot_pose = False
        self.have_map = False
        self.map_token = False
        self.map_compute = False

        # Holds the occupancy grid map
        self.ogm = 0
        self.ros_ogm = 0
        self.ogm_copy = 0

        # Holds the ogm info for copying reasons -- do not change
        self.ogm_info = 0
        self.prev_ogm_info = 0

        # Holds the robot's total path
        self.robot_trajectory = []
        self.previous_trajectory_length = 0

        # Holds the coverage information. This has the same size as the ogm
        # If a cell has the value of 0 it is uncovered
        # In the opposite case the cell's value will be 100
        self.coverage = []

        # Holds the resolution of the occupancy grid map
        self.resolution = 0.05

        # Origin is the translation between the (0,0) of the robot pose and the
        # (0,0) of the map
        self.origin = {}
        self.origin['x'] = 0
        self.origin['y'] = 0

        # Initialization of robot pose
        # x,y are in meters
        # x_px, y_px are in pixels
        self.robot_pose = {}
        self.robot_pose['x'] = 0
        self.robot_pose['y'] = 0
        self.robot_pose['th'] = 0
        self.robot_pose['x_px'] = 0
        self.robot_pose['y_px'] = 0

        self.coverage_ogm = OccupancyGrid()
        self.coverage_ogm.header.frame_id = "map"

        ogm_topic = rospy.get_param('ogm_topic')
        robot_trajectory_topic = rospy.get_param('robot_trajectory_topic')
        coverage_pub_topic = rospy.get_param('coverage_pub_topic')
        self.map_frame = rospy.get_param('map_frame')
        self.base_footprint_frame = rospy.get_param('base_footprint_frame')

        # Use tf to read the robot pose
        self.listener = tf.TransformListener()

        # Read robot pose with a timer
        rospy.Timer(rospy.Duration(0.11), self.readRobotPose)

        # ROS Subscriber to the occupancy grid map
        ogm_topic = rospy.get_param('ogm_topic')
        rospy.Subscriber(ogm_topic, OccupancyGrid, self.readMap)

        # Publisher of the robot trajectory
        robot_trajectory_topic = rospy.get_param('robot_trajectory_topic')
        self.robot_trajectory_publisher = rospy.Publisher(robot_trajectory_topic,\
                Path, queue_size = 10)

        # Publisher of the coverage field
        coverage_pub_topic = rospy.get_param('coverage_pub_topic')
        self.coverage_publisher = rospy.Publisher(coverage_pub_topic, \
            OccupancyGrid, queue_size = 10)

        # Read Cell size
        self.cell_size = rospy.get_param('cell_size')
        self.cell_matrix = numpy.zeros((1, 1))
        self.current_cell = []

        Print.art_print("Robot perception initialized", Print.GREEN)
Ejemplo n.º 28
0
    def selectTarget(self):

        # Cancel previous goal timer
        self.timerThread.stop()

        # IMPORTANT: The robot must be stopped if you call this function until
        # it is over
        # Check if we have a map
        while self.robot_perception.have_map == False:
          Print.art_print("Navigation: No map yet", Print.RED)
          return

        print "\nClearing all markers"
        RvizHandler.printMarker(\
            [[0, 0]],\
            1, # Type: Arrow
            3, # Action: delete all
            "map", # Frame
            "null", # Namespace
            [0,0,0,0], # Color RGBA
            0.1 # Scale
        )

        print '\n\n----------------------------------------------------------'
        print "Navigation: Producing new target"
        # We are good to continue the exploration
        # Make this true in order not to call it again from the speeds assignment
        self.target_exists = True

        # Gets copies of the map and coverage
        local_ogm = self.robot_perception.getMap()
        local_ros_ogm = self.robot_perception.getRosMap()
        local_coverage = self.robot_perception.getCoverage()
        print "Got the map and Coverage"
        self.path_planning.setMap(local_ros_ogm)

        # Once the target has been found, find the path to it
        # Get the global robot pose
        g_robot_pose = self.robot_perception.getGlobalCoordinates(\
              [self.robot_perception.robot_pose['x_px'],\
              self.robot_perception.robot_pose['y_px']])

        # Call the target selection function to select the next best goal
        # Choose target function
        self.path = []
        force_random = False

        # Potential Target
        path_altered = False
        previous_target = None

        while len(self.path) == 0:
          start = time.time()
          target = self.target_selection.selectTarget(\
                    local_ogm,\
                    local_coverage,\
                    self.robot_perception.robot_pose,
                    self.robot_perception.origin,
                    self.robot_perception.resolution,
                    force_random)

          # ipdb.set_trace()
          # Check if there was any path alteration
          if target[0] == True:
              previous_target = target[2]
              target = target[1]
              path_altered = True
          else:
              target = target[1]

          self.path = self.path_planning.createPath(\
              g_robot_pose,\
              target,
              self.robot_perception.resolution)
          print "Navigation: Path for target found with " + str(len(self.path)) +\
              " points"
          if len(self.path) == 0:
            Print.art_print(\
                "Path planning failed. Fallback to random target selection", \
                Print.RED)
            force_random = True

        # Reverse the path to start from the robot
        self.path = self.path[::-1]

        # Break the path to subgoals every 2 pixels (1m = 20px)
        step = 1
        n_subgoals = (int) (len(self.path)/step)
        self.subtargets = []
        for i in range(0, n_subgoals):
          self.subtargets.append(self.path[i * step])
        self.subtargets.append(self.path[-1])
        self.next_subtarget = 0
        print "The path produced " + str(len(self.subtargets)) + " subgoals"

        ######################### NOTE: QUESTION  ##############################
        # The path is produced by an A* algorithm. This means that it is
        # optimal in length but 1) not smooth and 2) length optimality
        # may not be desired for coverage-based exploration
        ########################################################################

        # Start timer thread
        self.timerThread.start()

        # Publish the path for visualization purposes
        ros_path = Path()
        ros_path.header.frame_id = "map"
        for p in self.path:
          ps = PoseStamped()
          ps.header.frame_id = "map"
          ps.pose.position.x = 0
          ps.pose.position.y = 0

          ######################### NOTE: QUESTION  ##############################
          # Fill the ps.pose.position values to show the path in RViz
          # You must understand what self.robot_perception.resolution
          # and self.robot_perception.origin are.
          # ipdb.set_trace()
          ps.pose.position.x = p[0] * self.robot_perception.resolution \
              + self.robot_perception.origin['x']
          ps.pose.position.y = p[1] * self.robot_perception.resolution \
              + self.robot_perception.origin['y']
          ########################################################################

          ros_path.poses.append(ps)
        self.path_publisher.publish(ros_path)

        # Publish the subtargets for visualization purposes
        subtargets_mark = []
        for s in self.subtargets:
          subt = [
            s[0] * self.robot_perception.resolution + \
                    self.robot_perception.origin['x'],
            s[1] * self.robot_perception.resolution + \
                    self.robot_perception.origin['y']
            ]
          subtargets_mark.append(subt)

        RvizHandler.printMarker(\
            subtargets_mark,\
            2, # Type: Sphere
            0, # Action: Add
            "map", # Frame
            "art_subtargets", # Namespace
            [0, 0.8, 0.0, 0.8], # Color RGBA
            0.2 # Scale
        )

        # Print Old and Current Final Target
        if path_altered == True:
            subt = [
            previous_target[0] * self.robot_perception.resolution + \
                    self.robot_perception.origin['x'],
            previous_target[1] * self.robot_perception.resolution + \
                    self.robot_perception.origin['y']
            ]
            # ipdb.set_trace()

            RvizHandler.printMarker(\
                [subt],\
                3, # Type: Sphere
                0, # Action: Add
                "map", # Frame
                "art_subtargets", # Namespace
                [1.0, 0.0, 0.0, 0.8], # Color RGBA
                0.2 # Scale
            )

        # ipdb.set_trace()
        self.inner_target_exists = True
Ejemplo n.º 29
0
    def selectTarget(self, init_ogm, ros_ogm, coverage, robot_pose, origin, \
        resolution, force_random = False):

        target = [-1, -1]

        ######################### NOTE: QUESTION  ##############################
        # Implement a smart way to select the next target. You have the
        # following tools: ogm_limits, Brushfire field, OGM skeleton,
        # topological nodes.

        # Find only the useful boundaries of OGM. Only there calculations
        # have meaning
        ogm_limits = OgmOperations.findUsefulBoundaries(
            init_ogm, origin, resolution)

        # Blur the OGM to erase discontinuities due to laser rays
        ogm = OgmOperations.blurUnoccupiedOgm(init_ogm, ogm_limits)

        # Calculate Brushfire field
        tinit = time.time()
        brush = self.brush.obstaclesBrushfireCffi(ogm, ogm_limits)
        Print.art_print("Brush time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Calculate skeletonization
        tinit = time.time()
        skeleton = self.topo.skeletonizationCffi(ogm, \
                   origin, resolution, ogm_limits)
        Print.art_print("Skeletonization time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Find topological graph
        tinit = time.time()
        nodes = self.topo.topologicalNodes(ogm, skeleton, coverage, origin, \
                resolution, brush, ogm_limits)
        Print.art_print("Topo nodes time: " + str(time.time() - tinit),
                        Print.ORANGE)

        # Visualization of topological nodes
        vis_nodes = []
        for n in nodes:
            vis_nodes.append([
                n[0] * resolution + origin['x'],
                n[1] * resolution + origin['y']
            ])
        RvizHandler.printMarker(\
            vis_nodes,\
            1, # Type: Arrow
            0, # Action: Add
            "map", # Frame
            "art_topological_nodes", # Namespace
            [0.3, 0.4, 0.7, 0.5], # Color RGBA
            0.1 # Scale
        )
        # Random point
        if self.method == 'random' or force_random == True:
            target = self.selectRandomTarget(ogm, coverage, brush, ogm_limits)
        # Custom point
        elif self.method == 'cost_based':
            self.path_planning.setMap(ros_ogm)
            g_robot_pose = [robot_pose['x_px'] - int(origin['x'] / resolution),\
                            robot_pose['y_px'] - int(origin['y'] / resolution)]

            # Remove all covered nodes from the candidate list
            nodes = np.array(nodes)
            uncovered_idxs = np.array(
                [coverage[n[0], n[1]] == 0 for n in nodes])
            goals = nodes[uncovered_idxs]

            # Initialize costs
            w_dist = np.full(len(goals), np.inf)
            w_turn = np.full(len(goals), np.inf)
            w_topo = np.full(len(goals), np.inf)
            w_cove = np.full(len(goals), np.inf)

            for idx, node in zip(range(len(goals)), goals):
                subgoals = np.array(
                    self.path_planning.createPath(g_robot_pose, node,
                                                  resolution))

                # If path is empty then skip to the next iteration
                if subgoals.size == 0:
                    continue

                # subgoals should contain the robot pose, so we don't need to diff it explicitly
                subgoal_vectors = np.diff(subgoals, axis=0)

                # Distance cost
                dists = [math.hypot(v[0], v[1]) for v in subgoal_vectors]
                w_dist[idx] = np.sum(dists)

                # Turning cost
                w_turn[idx] = 0
                theta = robot_pose['th']

                for v in subgoal_vectors[:-1]:
                    st_x, st_y = v
                    theta2 = math.atan2(st_y - g_robot_pose[1],
                                        st_x - g_robot_pose[0])
                    w_turn[idx] += abs(theta2 - theta)
                    theta = theta2

                # Coverage cost
                w_cove[idx] = sum(coverage[x][y] for x, y in subgoal_vectors)

                # Topology cost
                w_topo[idx] = brush[node[0], node[1]]

            # Normalize weights
            w_dist = (w_dist - min(w_dist)) / (max(w_dist) - min(w_dist))
            w_turn = (w_turn - min(w_turn)) / (max(w_turn) - min(w_turn))
            w_cove = (w_cove - min(w_cove)) / (max(w_cove) - min(w_cove))
            w_topo = (w_topo - min(w_topo)) / (max(w_topo) - min(w_topo))

            # Cost weights
            c_topo = 4
            c_dist = 3
            c_cove = 2
            c_turn = 1

            # Calculate combination cost (final)
            cost = c_dist * w_dist + c_turn * w_turn + c_cove * w_cove + c_topo * w_topo
            min_dist, min_idx = min(zip(cost, range(len(cost))))
            target = nodes[min_idx]

            # Check if next target exists and if it exists, check if is close to previous
            if target is None:
                target = self.selectRandomTarget(ogm, coverage, brush,
                                                 ogm_limits)
            else:
                target_dist = math.hypot(target[0] - self.previous_target[0],
                                         target[1] - self.previous_target[1])
                if target_dist <= 5:
                    target = self.selectRandomTarget(ogm, coverage, brush,
                                                     ogm_limits)
        ########################################################################
        self.previous_target = target
        return target
Ejemplo n.º 30
0
    def checkTarget(self, event):
        # Check if we have a target or if the robot just wanders
        if self.inner_target_exists == False or self.move_with_target == False or\
                self.next_subtarget == len(self.subtargets):
          return

        # Check if timer has expired
        if self.timerThread.expired == True:
          Print.art_print('\n~~~~ Time reset ~~~~',Print.RED)
          self.inner_target_exists = False
          self.target_exists = False
          return

        # Get the robot pose in pixels
        [rx, ry] = [\
            self.robot_perception.robot_pose['x_px'] - \
                    self.robot_perception.origin['x'] / self.robot_perception.resolution,\
            self.robot_perception.robot_pose['y_px'] - \
                    self.robot_perception.origin['y'] / self.robot_perception.resolution\
                    ]

        theta_robot = self.robot_perception.robot_pose['th']

        # Clear achieved targets
        self.subtargets = self.subtargets[self.next_subtarget:]
        self.next_subtarget = 0

        # Find the distance between the robot pose and all remaining subtargets
        dx = [rx - st[0] for st in self.subtargets]
        dy = [ry - st[1] for st in self.subtargets]
        dist = [math.hypot(v[0], v[1]) for v in zip(dx, dy)]

        # Try to optimize path only when there is more than one target available
        if len(self.subtargets) > 1:
          ogm = self.robot_perception.getMap()

          theta_goals = np.arctan2(-np.array(dy),-np.array(dx))
          dtheta = theta_goals - theta_robot
          dtheta[dtheta > np.pi] -= 2*np.pi
          dtheta[dtheta < -np.pi] += 2*np.pi

          # Check if there are obstacles between robot and subtarget
          obstacles_subtarget = []
          for st,i in zip(self.subtargets, range(len(self.subtargets))):
            # Find line in pixels between robot and goal
            line_pxls = list(bresenham(int(round(st[0])), int(round(st[1])),\
                                       int(round(rx)), int(round(ry))))
            # Find if there are any obstacles in line
            ogm_line = list(map(lambda pxl: ogm[pxl[0], pxl[1]], line_pxls))
            N_occupied = len(list(filter(lambda x: x > 80, ogm_line)))
            obstacles_subtarget.append(N_occupied)

          # Check if one of next goals is aligned with the current robot theta
          # In this case plan immediately for this goal in order to improve motion behaviour
          for st, i in zip(self.subtargets, range(len(self.subtargets))):
            if np.fabs(dtheta[i]) < np.pi/10 and obstacles_subtarget[i] == 0:
              self.next_subtarget = i
              # Keep resetting  timer, while moving towards target (without any obstacles inbetween)
              self.timerThread.reset()

        # Check if any target is in distance
        min_dist, min_idx = min(zip(dist, range(len(dist))))

        if min_dist < 5:
          self.next_subtarget = min_idx + 1
          # Reset timer if a goal has been reached
          self.timerThread.reset()
          # Check if the final subtarget has been approached
          if self.next_subtarget >= len(self.subtargets):
            self.target_exists = False

        # Publish the current target
        if self.next_subtarget >= len(self.subtargets):
            return

        subtarget = [\
            self.subtargets[self.next_subtarget][0]\
                * self.robot_perception.resolution + \
                self.robot_perception.origin['x'],
            self.subtargets[self.next_subtarget][1]\
                * self.robot_perception.resolution + \
                self.robot_perception.origin['y']\
            ]

        RvizHandler.printMarker(\
            [subtarget],\
            1, # Type: Arrow
            0, # Action: Add
            "map", # Frame
            "art_next_subtarget", # Namespace
            [0, 0, 0.8, 0.8], # Color RGBA
            0.2 # Scale
        )