Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Dev/gui #9

Open
wants to merge 15 commits into
base: main
Choose a base branch
from
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,7 @@ add_message_files(
thrustermove.msg
trajectory.msg
translation.msg
system_stats.msg
cst0 marked this conversation as resolved.
Show resolved Hide resolved
)

## Generate services in the 'srv' folder
Expand Down
5 changes: 0 additions & 5 deletions msg/magnetometer.msg

This file was deleted.

2 changes: 2 additions & 0 deletions msg/system_stats.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
float32 cpu_usage
float32 temp
File renamed without changes.
76 changes: 76 additions & 0 deletions plugins/imu/nxp-by-file.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
#!/usr/bin/env python

"""

This file is part of Enbarr.

Enbarr is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.

Enbarr is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.

You should have received a copy of the GNU General Public License
along with Enbarr. If not, see <https://www.gnu.org/licenses/>.

"""

import rospy
from auv.msg import ninedof, gyroscope
# from auv.msg import gyroscope

import csv
import subprocess
import os

nineDof_current_pub = rospy.Publisher('ninedof_current', ninedof, queue_size=3)
nineDof_integrated_pub = rospy.Publisher('ninedof_integrated', gyroscope, queue_size=3)
nineDof_gyro_pub = rospy.Publisher('ninedof_gyroscope', gyroscope, queue_size=3)


def listener():
rospy.init_node('nxp-by-file_nineDof', anonymous=True)
rate = rospy.Rate(5)
proc = subprocess.Popen('rosrun auv read_nxpval.py', shell=True)

sendval_ninedof = ninedof()
sendval_integrated = gyroscope()
sendval_gyro = gyroscope()
current_directory = os.path.dirname(__file__)
csv_filename = os.path.join(current_directory, '../scripts/output/nxpval.csv')
while not rospy.is_shutdown():

with open(csv_filename, "r") as f:
reader = csv.DictReader(f)

for row in reader:
sendval_ninedof.orientation.roll = row['roll']
sendval_ninedof.orientation.pitch = row['pitch']
sendval_ninedof.orientation.yaw = row['yaw']
sendval_ninedof.translation.x = row['accl_x']
sendval_ninedof.translation.y = row['accl_y']
sendval_ninedof.translation.z = row['accl_z']

sendval_integrated.x = row['pos_x']
sendval_integrated.y = row['pos_y']
sendval_integrated.z = row['pos_z']

sendval_gyro.x = row['gyro_x']
sendval_gyro.y = row['gyro_y']
sendval_gyro.z = row['gyro_z']

nineDof_current_pub.publish(sendval_ninedof)
nineDof_integrated_pub.publish(sendval_integrated)
nineDof_gyro_pub.publish(sendval_gyro)

rate.sleep()

proc.kill()


if __name__ == '__main__':
listener()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

it's not clear to me what happened with this file so I don't know why it's showing up in this commit, but I do recall regretting the fact that it was written (not by me). I'm guessing it's just a file rename?

File renamed without changes.
Empty file removed plugins/sensors/__init__.py
Empty file.
31 changes: 31 additions & 0 deletions scripts/vehicle_stats.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
#!/usr/bin/env python3

import rospy
from scripts.trajectory_sender_test import publisher
from wurov.msg import system_stats
import psutil
from gpiozero import CPUTemperature

class vehicle_stats:
def __init__(self):
rospy.init_node('vehicle_stats', anonymous=True)

self.nineDof_current_pub = rospy.Publisher(
'vehicle_stats', system_stats, queue_size=3)


rospy.Timer(rospy.Duration(4, self.publisher)

rospy.spin()

def publisher(self, data):
ret_msg = system_stats()
ret_msg.cpu_usage = psutil.cpu_percent()

cpu = CPUTemperature()

ret_msg.temp = cpu.temperature

self.publisher.publish(ret_msg)
if __name__ == '__main__':
vehicle_stats()
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this node just needed a bit of tweaking since there was a missing paren. Also note that 'Duration' doesn't operate in Hz, so if you want this called at 4 hz you have to give it a duration of 1/4. Also, although the timer takes in a parameter, it's there to denote event information (expected duration vs. actual duration). Finally, there were 3 different things called 'publisher', so I just removed the unused import and renamed the class variable.

181 changes: 181 additions & 0 deletions surface/UI/debug_ui.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,181 @@
#!/usr/bin/env python3

from PySide2 import QtCore, QtGui, QtWidgets
from PySide2.QtCore import QTimer
from PySide2.QtWidgets import QApplication, QWidget
from PySide2.QtGui import *
from PySide2.QtWidgets import *
from PySide2.QtCore import *
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

better practice is to use singular imports

import os
import sys
import rospy
import math
from PySide2extn.RoundProgressBar import roundProgressBar
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

and also good practice would be to sort these a tad


from wurov.msg import system_stats
from sensor_msgs.msg import Imu, MagneticField

# Configurations
fullscreenMode = True
cameraIndex1 = 2
cameraIndex2 = 1
# Enter Screen Resolution for surface station(Only if fullscreenMode is disabled)
height = 1080
width = 1920
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

global scoped constant variables that are lowercase (instead of conventional ALL_CAPS)? Alternatively, since you know the goal is for this to be full-screen, you could just collect those resolution values and go from there.

# Fonts
Header = QtGui.QFont("Roboto", 12, QtGui.QFont.Bold)
Body = QtGui.QFont("Roboto", 10)


class WUROV(QWidget):
def __init__(self):
rospy.init_node('gui', anonymous=True)
rospy.Subscriber('imu/data_raw', Imu, self.update_raw_imu)
rospy.Subscriber('imu/data', Imu, self.update_filtered_imu)

# Style settings for GUI
super(WUROV, self).__init__()
self.setGeometry(0, 0, width, height)
self.setWindowTitle("WUROV Control")
self.setStyleSheet('background-color: ' +
'#2C2F33' + ';color: ' + 'white')

# Grid layout for GUI
self.nineDof()
grid = QtWidgets.QGridLayout()

grid.addWidget(self.raw_title, 1, 0)
grid.addWidget(self.raw_accel_x, 2, 0)
grid.addWidget(self.raw_accel_y, 3, 0)
grid.addWidget(self.raw_accel_z, 4, 0)
grid.addWidget(self.raw_ang_x, 5, 0)
grid.addWidget(self.raw_ang_y, 6, 0)
grid.addWidget(self.raw_ang_z, 7, 0)

grid.addWidget(self.filtered_title, 1, 1)
grid.addWidget(self.filtered_accel_x, 2, 1)
grid.addWidget(self.filtered_accel_y, 3, 1)
grid.addWidget(self.filtered_accel_z, 4, 1)
grid.addWidget(self.filtered_ang_x, 5, 1)
grid.addWidget(self.filtered_ang_y, 6, 1)
grid.addWidget(self.filtered_ang_z, 7, 1)

grid.addWidget(self.speed_title, 1, 2)
grid.addWidget(self.speed, 2, 2)
self.setLayout(grid)

# NineDof labels to display sensor read outs

def nineDof(self):
# raw ninedof
self.raw_title = QtWidgets.QLabel(self)
self.raw_title.setFont(QtGui.QFont(Header))
self.raw_title.adjustSize()
self.raw_title.setText("Raw IMU: ")

self.raw_accel_x = QtWidgets.QLabel(self)
self.raw_accel_x.setFont(QtGui.QFont(Body))
self.raw_accel_x.adjustSize()

self.raw_accel_y = QtWidgets.QLabel(self)
self.raw_accel_y.setFont(QtGui.QFont(Body))
self.raw_accel_y.adjustSize()

self.raw_accel_z = QtWidgets.QLabel(self)
self.raw_accel_z.setFont(QtGui.QFont(Body))
self.raw_accel_z.adjustSize()

self.raw_ang_x = QtWidgets.QLabel(self)
self.raw_ang_x.setFont(QtGui.QFont(Body))
self.raw_ang_x.adjustSize()

self.raw_ang_y = QtWidgets.QLabel(self)
self.raw_ang_y.setFont(QtGui.QFont(Body))
self.raw_ang_y.adjustSize()

self.raw_ang_z = QtWidgets.QLabel(self)
self.raw_ang_z.setFont(QtGui.QFont(Body))
self.raw_ang_z.adjustSize()
# filtered ninedof
self.filtered_title = QtWidgets.QLabel(self)
self.filtered_title.setFont(QtGui.QFont(Header))
self.filtered_title.adjustSize()
self.filtered_title.setText("Filtered IMU: ")

self.filtered_accel_x = QtWidgets.QLabel(self)
self.filtered_accel_x.setFont(QtGui.QFont(Body))
self.filtered_accel_x.adjustSize()

self.filtered_accel_y = QtWidgets.QLabel(self)
self.filtered_accel_y.setFont(QtGui.QFont(Body))
self.filtered_accel_y.adjustSize()

self.filtered_accel_z = QtWidgets.QLabel(self)
self.filtered_accel_z.setFont(QtGui.QFont(Body))
self.filtered_accel_z.adjustSize()

self.filtered_ang_x = QtWidgets.QLabel(self)
self.filtered_ang_x.setFont(QtGui.QFont(Body))
self.filtered_ang_x.adjustSize()

self.filtered_ang_y = QtWidgets.QLabel(self)
self.filtered_ang_y.setFont(QtGui.QFont(Body))
self.filtered_ang_y.adjustSize()

self.filtered_ang_z = QtWidgets.QLabel(self)
self.filtered_ang_z.setFont(QtGui.QFont(Body))
self.filtered_ang_z.adjustSize()
# speedometer
self.speed_title = QtWidgets.QLabel(self)
self.speed_title.setFont(QtGui.QFont(Header))
self.speed_title.adjustSize()
self.speed_title.setText("Speed Data: ")

self.speed = roundProgressBar()
self.speed.rpb_setRange(0, 1.5)
self.speed.rpb_setTextFormat('Value')

# Update functions change labels based on callback
def update_raw_imu(self, data):
self.raw_accel_x.setText(f"Accel X: {data.linear_acceleration.x}")
self.raw_accel_y.setText(f"Accel Y: {data.linear_acceleration.y}")
self.raw_accel_z.setText(f"Accel Z: {data.linear_acceleration.z}")
self.raw_ang_x.setText(f"Angular X: {data.angular_velocity.x}")
self.raw_ang_y.setText(f"Angular Y: {data.angular_velocity.y}")
self.raw_ang_z.setText(f"Angular Z: {data.angular_velocity.z}")

def update_filtered_imu(self, data):
self.filtered_accel_x.setText(f"Accel X: {data.linear_acceleration.x}")
self.filtered_accel_y.setText(f"Accel Y: {data.linear_acceleration.y}")
self.filtered_accel_z.setText(f"Accel Z: {data.linear_acceleration.z}")
self.filtered_ang_x.setText(f"Angular X: {data.angular_velocity.x}")
self.filtered_ang_y.setText(f"Angular Y: {data.angular_velocity.y}")
self.filtered_ang_z.setText(f"Angular Z: {data.angular_velocity.z}")

acel_mag = math.sqrt(data.linear_acceleration.x**2 +
data.linear_acceleration.y**2 + data.linear_acceleration.z**2)
self.speed.rpb_setValue(acel_mag)

def alert(self, s):
"""
This handle errors and displaying alerts.
"""
err = QErrorMessage(self)
err.showMessage(s)


# Code to be executed
if __name__ == "__main__":
import sys
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

why is this import here and not up at the top? Also, you may need to make use of rospy.myargv if you plan on running this as a node.


app = QApplication(sys.argv)
win = WUROV()

def window():
if fullscreenMode:
win.showFullScreen()
else:
win.show()
sys.exit(app.exec_())

window()
Binary file added surface/UI/default.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading