diff --git a/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMap.py b/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMap.py index a42fe1f..8cee877 100644 --- a/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMap.py +++ b/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMap.py @@ -440,14 +440,15 @@ class OverlayImage(object): for element in navigation_list: x, y = self._get_cartesian(float(element[1]), float(element[2])) - draw.ellipse((x - size, y - size, x + size, y + size), fill="red") + draw.text((x + 10, y - 5), str(element[0])) + draw.ellipse((x - size, y - size, x + size, y + size), fill=(element[3].red(), element[3].green(), element[3].blue())) for element in landmark_list: x, y = self._get_cartesian(element[1], element[2]) - draw.ellipse((x - size, y - size, x + size, y + size), fill="blue") + draw.text((x + 10, y - 5), str(element[0])) + draw.ellipse((x - size, y - size, x + size, y + size), fill=(element[3].red(), element[3].green(), element[3].blue())) self._draw_rover(latitude, longitude, compass) - # self._draw_coordinate_text(latitude, longitude) self.update(latitude, longitude) return self.display_image @@ -455,8 +456,6 @@ class OverlayImage(object): def load_rover_icon(self): self.indicator = PIL.Image.open("Resources/Images/rover.png").resize((40, 40)) - - def _draw_rover(self, lat, lon, angle=0): x, y = self._get_cartesian(lat, lon) diff --git a/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py b/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py index acbb888..d9959b1 100644 --- a/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py +++ b/software/ros_packages/ground_station/src/Framework/MapSystems/RoverMapCoordinator.py @@ -68,8 +68,8 @@ class RoverMapCoordinator(QtCore.QThread): self.map_pixmap = QtGui.QPixmap.fromImage(ImageQt(Image.open("Resources/Images/maps_loading.png").resize((1280, 720), Image.BICUBIC))) self.last_map_pixmap_cache_key = None - self.longitude = None - self.latitude = None + self.longitude = 0 + self.latitude = 0 self.last_heading = 0 self.imu_data = None @@ -168,7 +168,11 @@ class RoverMapCoordinator(QtCore.QThread): self.pixmap_ready_signal.emit() def _draw_coordinate_text(self, latitude, longitude): - location_text = "LAT: %+014.9f\nLON: %+014.9f" % (latitude, longitude) + + if latitude == 0 and longitude == 0: + location_text = "LAT: NO FIX\nLON: NO FIX" + else: + location_text = "LAT: %+014.9f\nLON: %+014.9f" % (latitude, longitude) font = PIL.ImageFont.truetype("UbuntuMono-R", size=20) @@ -204,29 +208,29 @@ class RoverMapCoordinator(QtCore.QThread): temp_list = [] count = UI_element.rowCount() for row in range(0, count): - num = UI_element.item(row, 0).text() + name = UI_element.item(row, 0).text() lat = float(UI_element.item(row, 1).text()) lng = float(UI_element.item(row, 2).text()) - temp_tuple = (num, lat, lng) + color = UI_element.item(row, 3).background().color() + temp_tuple = (name, lat, lng, color) temp_list.append(temp_tuple) return temp_list def update_overlay(self): - if self.latitude and self.longitude: - if not numpy.isnan(self.latitude) and not numpy.isnan(self.longitude): - latitude = float(self.latitude) - longitude = float(self.longitude) + if not numpy.isnan(self.latitude) and not numpy.isnan(self.longitude): + latitude = float(self.latitude) + longitude = float(self.longitude) - navigation_list = self._get_table_elements(self.navigation_label) - landmark_list = self._get_table_elements(self.landmark_label) - self.overlay_image = self.overlay_image_object.update_new_location( - latitude, - longitude, - self.last_heading, - navigation_list, - landmark_list) - # self.last_heading = (self.last_heading + 5) % 360 - # self.overlay_image.save("something.png") + navigation_list = self._get_table_elements(self.navigation_label) + landmark_list = self._get_table_elements(self.landmark_label) + self.overlay_image = self.overlay_image_object.update_new_location( + latitude, + longitude, + self.last_heading, + navigation_list, + landmark_list) + # self.last_heading = (self.last_heading + 5) % 360 + # self.overlay_image.save("something.png") def gps_position_updated_callback(self, data): self.latitude = data.latitude diff --git a/software/ros_packages/ground_station/src/Framework/NavigationSystems/WaypointsCoordinator.py b/software/ros_packages/ground_station/src/Framework/NavigationSystems/WaypointsCoordinator.py index 19b250c..0c1c459 100644 --- a/software/ros_packages/ground_station/src/Framework/NavigationSystems/WaypointsCoordinator.py +++ b/software/ros_packages/ground_station/src/Framework/NavigationSystems/WaypointsCoordinator.py @@ -44,6 +44,13 @@ class WaypointsCoordinator(QtCore.QThread): self.longitude_card_label = self.left_screen.manual_waypoint_cardinal_longitude_combo_box + # Color Labels and Buttons + self.nav_color_label = self.left_screen.manual_waypoint_navigation_color_label + self.nav_color_set_button = self.left_screen.manual_waypoint_navigation_color_set_button + + self.landmark_color_label = self.left_screen.manual_waypoint_landmark_color_label + self.landmark_color_set_button = self.left_screen.manual_waypoint_landmark_color_set_button + # Nav Table Buttons self.nav_set_button_label = (self.left_screen. navigation_waypoints_set_button) @@ -77,6 +84,17 @@ class WaypointsCoordinator(QtCore.QThread): self.longitude = None self.latitude = None + self.nav_color = QtCore.Qt.yellow + self.landmark_color = QtCore.Qt.blue + + self.nav_color_dialog = QtWidgets.QColorDialog() + self.nav_color_dialog.setWindowFlags( + QtCore.Qt.WindowStaysOnTopHint | QtCore.Qt.X11BypassWindowManagerHint | QtCore.Qt.WindowTitleHint | QtCore.Qt.WindowCloseButtonHint) + + self.landmark_color_dialog = QtWidgets.QColorDialog() + self.landmark_color_dialog.setWindowFlags( + QtCore.Qt.WindowStaysOnTopHint | QtCore.Qt.X11BypassWindowManagerHint | QtCore.Qt.WindowTitleHint | QtCore.Qt.WindowCloseButtonHint) + def run(self): while self.run_thread_flag: self.msleep(3) @@ -100,13 +118,22 @@ class WaypointsCoordinator(QtCore.QThread): self.navigation_label.cellClicked.connect(self._on_nav_clicked) self.landmark_label.cellClicked.connect(self._on_land_clicked) - def _add_to_table(self, name, lat, lng, dist, table): + self.nav_color_set_button.clicked.connect(self.nav_color_dialog.show) + self.landmark_color_set_button.clicked.connect(self.landmark_color_dialog.show) + + self.nav_color_dialog.currentColorChanged.connect(self.__on_new_nav_color_selected) + self.landmark_color_dialog.currentColorChanged.connect(self.__on_new_landmark_color_selected) + + def _add_to_table(self, name, lat, lng, color, table): + color_table_item = QtWidgets.QTableWidgetItem() + color_table_item.setBackground(color) + count = table.rowCount() table.insertRow(count) table.setItem(count, 0, QtWidgets.QTableWidgetItem(name)) table.setItem(count, 1, QtWidgets.QTableWidgetItem(lat)) table.setItem(count, 2, QtWidgets.QTableWidgetItem(lng)) - table.setItem(count, 3, QtWidgets.QTableWidgetItem(dist)) + table.setItem(count, 3, color_table_item) def _clear_inputs(self): self.name_edit_label.clear() @@ -125,9 +152,8 @@ class WaypointsCoordinator(QtCore.QThread): def _nav_add_gps(self): if self.longitude and self.latitude: name = self.navigation_label.rowCount() - distance = 0 # FIXME: this should be calculated from current to enterred position self._add_to_table(str(name + 1), str(self.latitude), - str(self.longitude), str(distance), + str(self.longitude), self.nav_color, self.navigation_label) self._clear_inputs() @@ -143,6 +169,14 @@ class WaypointsCoordinator(QtCore.QThread): self.navigation_table_cur_click, 2, QtWidgets.QTableWidgetItem(lng)) + + color_table_item = QtWidgets.QTableWidgetItem() + color_table_item.setBackground(self.nav_color) + + self.navigation_label.setItem( + self.navigation_table_cur_click, + 3, + color_table_item) self._clear_inputs() def _nav_add_manual(self): @@ -151,9 +185,8 @@ class WaypointsCoordinator(QtCore.QThread): name = self.navigation_label.rowCount() lat = self.latitude_label.text() lng = self.longitude_label.text() - distance = 200 self._add_to_table(str(name + 1), lat, - lng, str(distance), + lng, self.nav_color, self.navigation_label) self._clear_inputs() @@ -171,10 +204,7 @@ class WaypointsCoordinator(QtCore.QThread): def _land_add_gps(self): if self.longitude and self.latitude: name = self.name_edit_label.text() - distance = 200 # FIXME: this should be calculated from current to enterred position - self._add_to_table(name, str(self.latitude), - str(self.longitude), str(distance), - self.landmark_label) + self._add_to_table(name, str(self.latitude), str(self.longitude), self.landmark_color, self.landmark_label) self._clear_inputs() def _land_add_manual(self): @@ -182,9 +212,8 @@ class WaypointsCoordinator(QtCore.QThread): name = self.name_edit_label.text() lat = self.latitude_label.text() lng = self.longitude_label.text() - distance = 200 self._add_to_table(name, lat, - lng, str(distance), + lng, self.landmark_color, self.landmark_label) self._clear_inputs() @@ -213,6 +242,12 @@ class WaypointsCoordinator(QtCore.QThread): self.landmark_label.setItem(self.landmark_table_cur_click, 2, QtWidgets.QTableWidgetItem(lng)) + color_table_item = QtWidgets.QTableWidgetItem() + color_table_item.setBackground(self.landmark_color) + + self.landmark_label.setItem(self.landmark_table_cur_click, 3, + color_table_item) + self._clear_inputs() def setup_signals(self, start_signal, @@ -272,6 +307,18 @@ class WaypointsCoordinator(QtCore.QThread): 1 ) + def __on_new_nav_color_selected(self, color): + self.nav_color_label.setStyleSheet( + "background-color: rgb(%s, %s, %s)" % (color.red(), color.green(), color.blue())) + + self.nav_color = color + + def __on_new_landmark_color_selected(self, color): + self.landmark_color_label.setStyleSheet( + "background-color: rgb(%s, %s, %s)" % (color.red(), color.green(), color.blue())) + + self.landmark_color = color + def gps_position_updated_callback(self, data): self.latitude = data.latitude self.longitude = data.longitude diff --git a/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui b/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui index 2211f53..5efcd23 100644 --- a/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui +++ b/software/ros_packages/ground_station/src/Resources/Ui/left_screen.ui @@ -1892,6 +1892,125 @@ N/A + + + + 6 + + + + + + 75 + true + + + + Color + + + + + + + Qt::Vertical + + + + + + + Navigation + + + + + + + + 25 + 25 + + + + + 25 + 25 + + + + background-color:yellow; + + + + + + + + + + Set + + + + + + + Qt::Vertical + + + + + + + Landmark + + + + + + + + 25 + 25 + + + + + 25 + 25 + + + + background-color:blue; + + + + + + + + + + Set + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + @@ -2063,22 +2182,26 @@ N/A + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 9999999 + + - QTableView{ - selection-background-color: #DE8D47; -} - -QTableView QHeaderView{ - background-color: #201F1D; -} - -QTableView QHeaderView::section{ - background-color: #201F1D; -} - -QTableView QTableCornerButton::section{ - background-color: #201F1D; -} + Qt::ScrollBarAlwaysOff @@ -2116,16 +2239,6 @@ QTableView QTableCornerButton::section{ 30 - - - 1 - - - - - 2 - - # @@ -2143,49 +2256,9 @@ QTableView QTableCornerButton::section{ - Dist + Color - - - 1 - - - - - 44.5674 - - - - - -123.2756 - - - - - 2.4 KM - - - - - 2 - - - - - 44.5677 - - - - - -123.2748 - - - - - 5.7 KM - - @@ -2193,6 +2266,9 @@ QTableView QTableCornerButton::section{ 2 + + 4 + @@ -2207,11 +2283,13 @@ QTableView QTableCornerButton::section{ 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Set @@ -2232,11 +2310,13 @@ QTableView QTableCornerButton::section{ 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Add @@ -2258,11 +2338,13 @@ Manual 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Add @@ -2284,11 +2366,13 @@ GPS 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Delete @@ -2359,22 +2443,26 @@ GPS + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 9999999 + + - QTableView{ - selection-background-color: #DE8D47; -} - -QTableView QHeaderView{ - background-color: #201F1D; -} - -QTableView QHeaderView::section{ - background-color: #201F1D; -} - -QTableView QTableCornerButton::section{ - background-color: #201F1D; -} + Qt::ScrollBarAlwaysOff @@ -2415,16 +2503,6 @@ QTableView QTableCornerButton::section{ 30 - - - 1 - - - - - 2 - - Name @@ -2442,49 +2520,9 @@ QTableView QTableCornerButton::section{ - Dist + Color - - - Astronaut - - - - - 44.56745 - - - - - -123.2756 - - - - - 2.4 KM - - - - - Water - - - - - 44.56775 - - - - - -123.2748 - - - - - 5.7 KM - - @@ -2492,6 +2530,9 @@ QTableView QTableCornerButton::section{ 2 + + 4 + @@ -2506,11 +2547,13 @@ QTableView QTableCornerButton::section{ 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Set @@ -2531,11 +2574,13 @@ QTableView QTableCornerButton::section{ 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Add @@ -2557,11 +2602,13 @@ Manual 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Add @@ -2583,11 +2630,13 @@ GPS 35 + + + 8 + + - QPushButton{ - color: #201F1D; - background-color: #868685; -} + Delete