From 327c26becda2856eff648f40157e1d359b7490b6 Mon Sep 17 00:00:00 2001 From: neuenfeldttj Date: Fri, 5 Apr 2024 11:13:14 -0400 Subject: [PATCH 1/2] added comms to top --- src/teleoperation/backend/consumers.py | 37 ++++++++++++------- .../frontend/src/components/AutonTask.vue | 11 ++++-- .../frontend/src/components/BasicRoverMap.vue | 1 + .../frontend/src/components/DMESTask.vue | 10 ++++- .../frontend/src/components/ISHTask.vue | 16 ++++---- .../src/components/NetworkBandwidth.vue | 37 +++++++++++++++++++ .../frontend/src/components/SATask.vue | 24 ++++-------- 7 files changed, 91 insertions(+), 45 deletions(-) create mode 100644 src/teleoperation/frontend/src/components/NetworkBandwidth.vue diff --git a/src/teleoperation/backend/consumers.py b/src/teleoperation/backend/consumers.py index d86889ae0..526df60e4 100644 --- a/src/teleoperation/backend/consumers.py +++ b/src/teleoperation/backend/consumers.py @@ -31,6 +31,7 @@ Spectral, ScienceThermistors, HeaterData, + NetworkBandwidth ) from mrover.srv import EnableAuton, AdjustMotor, ChangeCameras, CapturePanorama from sensor_msgs.msg import NavSatFix, Temperature, RelativeHumidity, Image @@ -64,6 +65,20 @@ class GUIConsumer(JsonWebsocketConsumer): def connect(self): self.accept() try: + # ROS Parameters + self.mappings = rospy.get_param("teleop/joystick_mappings") + self.drive_config = rospy.get_param("teleop/drive_controls") + self.max_wheel_speed = rospy.get_param("rover/max_speed") + self.wheel_radius = rospy.get_param("wheel/radius") + self.max_angular_speed = self.max_wheel_speed / self.wheel_radius + self.ra_config = rospy.get_param("teleop/ra_controls") + self.ik_names = rospy.get_param("teleop/ik_multipliers") + self.RA_NAMES = rospy.get_param("teleop/ra_names") + self.brushless_motors = rospy.get_param("brushless_motors/controllers") + self.brushed_motors = rospy.get_param("brushed_motors/controllers") + self.xbox_mappings = rospy.get_param("teleop/xbox_mappings") + self.sa_config = rospy.get_param("teleop/sa_controls") + # Publishers self.twist_pub = rospy.Publisher("/cmd_vel", Twist, queue_size=1) self.led_pub = rospy.Publisher("/auton_led_cmd", String, queue_size=1) @@ -104,6 +119,7 @@ def connect(self): ) self.science_spectral = rospy.Subscriber("/science_spectral", Spectral, self.science_spectral_callback) self.cmd_vel = rospy.Subscriber("/cmd_vel", Twist, self.cmd_vel_callback) + self.network_bandwidth = rospy.Subscriber("/network_bandwidth", NetworkBandwidth, self.network_bandwidth_callback) # Services self.laser_service = rospy.ServiceProxy("enable_arm_laser", SetBool) @@ -116,20 +132,6 @@ def connect(self): self.capture_panorama_srv = rospy.ServiceProxy("capture_panorama", CapturePanorama) self.heater_auto_shutoff_srv = rospy.ServiceProxy("science_change_heater_auto_shutoff_state", SetBool) - # ROS Parameters - self.mappings = rospy.get_param("teleop/joystick_mappings") - self.drive_config = rospy.get_param("teleop/drive_controls") - self.max_wheel_speed = rospy.get_param("rover/max_speed") - self.wheel_radius = rospy.get_param("wheel/radius") - self.max_angular_speed = self.max_wheel_speed / self.wheel_radius - self.ra_config = rospy.get_param("teleop/ra_controls") - self.ik_names = rospy.get_param("teleop/ik_multipliers") - self.RA_NAMES = rospy.get_param("teleop/ra_names") - self.brushless_motors = rospy.get_param("brushless_motors/controllers") - self.brushed_motors = rospy.get_param("brushed_motors/controllers") - self.xbox_mappings = rospy.get_param("teleop/xbox_mappings") - self.sa_config = rospy.get_param("teleop/sa_controls") - self.tf_buffer = tf2_ros.Buffer() self.tf_listener = tf2_ros.TransformListener(self.tf_buffer) self.flight_thread = threading.Thread(target=self.flight_attitude_listener) @@ -610,6 +612,13 @@ def cmd_vel_callback(self, msg): ) ) + def network_bandwidth_callback(self, msg): + self.send( + text_data=json.dumps( + {"type": "network_bandwidth", "tx": msg.tx, "rx": msg.rx} + ) + ) + def gps_fix_callback(self, msg): self.send( text_data=json.dumps( diff --git a/src/teleoperation/frontend/src/components/AutonTask.vue b/src/teleoperation/frontend/src/components/AutonTask.vue index 0c36c1a89..ca65ec4ab 100644 --- a/src/teleoperation/frontend/src/components/AutonTask.vue +++ b/src/teleoperation/frontend/src/components/AutonTask.vue @@ -3,8 +3,8 @@

Auton Dashboard

- + +
Help
@@ -68,6 +68,7 @@ import OdometryReading from './OdometryReading.vue' import JoystickValues from './JoystickValues.vue' import DriveControls from './DriveControls.vue' import MastGimbalControls from './MastGimbalControls.vue' +import NetworkBandwidth from './NetworkBandwidth.vue' import { quaternionToMapAngle } from '../utils.js' import { defineComponent } from 'vue' @@ -84,7 +85,8 @@ export default defineComponent({ OdometryReading, JoystickValues, DriveControls, - MastGimbalControls + MastGimbalControls, + NetworkBandwidth }, data() { @@ -241,7 +243,8 @@ h2 { } .comms { - margin-right: 5px; + position: absolute; + right: 25%; } .helpscreen { diff --git a/src/teleoperation/frontend/src/components/BasicRoverMap.vue b/src/teleoperation/frontend/src/components/BasicRoverMap.vue index c59f54152..dc88bd1ed 100644 --- a/src/teleoperation/frontend/src/components/BasicRoverMap.vue +++ b/src/teleoperation/frontend/src/components/BasicRoverMap.vue @@ -221,5 +221,6 @@ export default { display: flex; align-items: center; height: 100%; + width: 100%; } diff --git a/src/teleoperation/frontend/src/components/DMESTask.vue b/src/teleoperation/frontend/src/components/DMESTask.vue index 6dffa10f1..67f33b280 100644 --- a/src/teleoperation/frontend/src/components/DMESTask.vue +++ b/src/teleoperation/frontend/src/components/DMESTask.vue @@ -4,6 +4,7 @@

ES GUI Dashboard

DM GUI Dashboard

+
Help
@@ -69,6 +70,7 @@ import MotorsStatusTable from './MotorsStatusTable.vue' import OdometryReading from './OdometryReading.vue' import DriveControls from './DriveControls.vue' import MastGimbalControls from './MastGimbalControls.vue' +import NetworkBandwidth from './NetworkBandwidth.vue' export default defineComponent({ components: { @@ -82,7 +84,8 @@ export default defineComponent({ MotorsStatusTable, OdometryReading, DriveControls, - MastGimbalControls + MastGimbalControls, + NetworkBandwidth }, props: { @@ -252,6 +255,11 @@ export default defineComponent({ transform: translateX(-50%); } +.comms { + position: absolute; + right: 25%; +} + .map { grid-area: map; } diff --git a/src/teleoperation/frontend/src/components/ISHTask.vue b/src/teleoperation/frontend/src/components/ISHTask.vue index 8be0a6a1c..028bc05a6 100644 --- a/src/teleoperation/frontend/src/components/ISHTask.vue +++ b/src/teleoperation/frontend/src/components/ISHTask.vue @@ -2,8 +2,8 @@

ISH Dashboard

- + +
Help @@ -44,13 +44,11 @@ + \ No newline at end of file diff --git a/src/teleoperation/frontend/src/components/SATask.vue b/src/teleoperation/frontend/src/components/SATask.vue index 45af1e6fa..1e1e3b5bf 100644 --- a/src/teleoperation/frontend/src/components/SATask.vue +++ b/src/teleoperation/frontend/src/components/SATask.vue @@ -2,8 +2,8 @@

SA Dashboard

- + +
Help @@ -78,13 +78,6 @@ :topic_name="'sa_calibrate_sensor_actuator'" />
-
@@ -107,11 +100,9 @@ import DriveMoteusStateTable from './DriveMoteusStateTable.vue' import MotorsStatusTable from './MotorsStatusTable.vue' import LimitSwitch from './LimitSwitch.vue' import CalibrationCheckbox from './CalibrationCheckbox.vue' -// import CommReadout from "./CommReadout.vue"; -// import MCUReset from "./MCUReset.vue"; -import MotorAdjust from './MotorAdjust.vue' import OdometryReading from './OdometryReading.vue' import SAArmControls from './SAArmControls.vue' +import NetworkBandwidth from './NetworkBandwidth.vue' import { disableAutonLED, quaternionToMapAngle } from '../utils.js' import { mapState } from 'vuex' @@ -128,11 +119,9 @@ export default { SAArmControls, LimitSwitch, CalibrationCheckbox, - // CommReadout, - // MCUReset, - MotorAdjust, OdometryReading, - MotorsStatusTable + MotorsStatusTable, + NetworkBandwidth }, data() { return { @@ -216,7 +205,8 @@ export default { } .comms { - margin-right: 5px; + position: absolute; + right: 25%; } .helpscreen { From 784d3807c924d85a98272a66034d800b4ec8a68f Mon Sep 17 00:00:00 2001 From: neuenfeldttj Date: Fri, 5 Apr 2024 11:25:21 -0400 Subject: [PATCH 2/2] format --- scripts/moteusConfigManage.py | 2 ++ src/teleoperation/backend/consumers.py | 18 ++++++------------ 2 files changed, 8 insertions(+), 12 deletions(-) diff --git a/scripts/moteusConfigManage.py b/scripts/moteusConfigManage.py index f2b2c5768..1886ec1f9 100755 --- a/scripts/moteusConfigManage.py +++ b/scripts/moteusConfigManage.py @@ -27,11 +27,13 @@ MOTEUS_SAVE_DIR = str(Path.cwd()) + "/config/moteus/" # Need to change this for other laptops. + def list_cfgs(): files = os.listdir(MOTEUS_SAVE_DIR) print("Saved configs:\n\t") print(*files, sep="\n\t") + def main(): command: str if len(sys.argv) >= 2: diff --git a/src/teleoperation/backend/consumers.py b/src/teleoperation/backend/consumers.py index 526df60e4..e84c2ae44 100644 --- a/src/teleoperation/backend/consumers.py +++ b/src/teleoperation/backend/consumers.py @@ -31,7 +31,7 @@ Spectral, ScienceThermistors, HeaterData, - NetworkBandwidth + NetworkBandwidth, ) from mrover.srv import EnableAuton, AdjustMotor, ChangeCameras, CapturePanorama from sensor_msgs.msg import NavSatFix, Temperature, RelativeHumidity, Image @@ -119,7 +119,9 @@ def connect(self): ) self.science_spectral = rospy.Subscriber("/science_spectral", Spectral, self.science_spectral_callback) self.cmd_vel = rospy.Subscriber("/cmd_vel", Twist, self.cmd_vel_callback) - self.network_bandwidth = rospy.Subscriber("/network_bandwidth", NetworkBandwidth, self.network_bandwidth_callback) + self.network_bandwidth = rospy.Subscriber( + "/network_bandwidth", NetworkBandwidth, self.network_bandwidth_callback + ) # Services self.laser_service = rospy.ServiceProxy("enable_arm_laser", SetBool) @@ -606,18 +608,10 @@ def drive_status_callback(self, msg): ) def cmd_vel_callback(self, msg): - self.send( - text_data=json.dumps( - {"type": "cmd_vel", "linear_x": msg.linear.x, "angular_z": msg.angular.z} - ) - ) + self.send(text_data=json.dumps({"type": "cmd_vel", "linear_x": msg.linear.x, "angular_z": msg.angular.z})) def network_bandwidth_callback(self, msg): - self.send( - text_data=json.dumps( - {"type": "network_bandwidth", "tx": msg.tx, "rx": msg.rx} - ) - ) + self.send(text_data=json.dumps({"type": "network_bandwidth", "tx": msg.tx, "rx": msg.rx})) def gps_fix_callback(self, msg): self.send(