mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 10:11:14 +00:00
Ubiquiti radio statuses now working. Misc other items.
This commit is contained in:
@@ -46,7 +46,7 @@ uint8_t message_count = 0;
|
||||
uint8_t failSafe;
|
||||
uint16_t lostFrames = 0;
|
||||
|
||||
uint16_t telem_24v_scalar = 37500;
|
||||
uint16_t telem_24v_scalar = 36680;
|
||||
|
||||
////////// Class Instantiations //////////
|
||||
SBUS x8r(SBUS_HARDWARE_PORT);
|
||||
|
||||
@@ -110,7 +110,7 @@ class SpaceNavControlSender(QtCore.QThread):
|
||||
|
||||
time_diff = time() - start_time
|
||||
|
||||
self.msleep(max(int(self.wait_time - time_diff), 0))
|
||||
self.msleep(max(int((self.wait_time - time_diff) * 1000), 0))
|
||||
|
||||
def process_spnav_events(self):
|
||||
event = spnav.spnav_poll_event()
|
||||
|
||||
@@ -18,6 +18,11 @@ FRSKY_TOPIC_NAME = "/rover_status/frsky_status"
|
||||
GPS_TOPIC_NAME = "/rover_status/gps_status"
|
||||
JETSON_TOPIC_NAME = "/rover_status/jetson_status"
|
||||
MISC_TOPIC_NAME = "/rover_status/misc_status"
|
||||
BATTERY_TOPIC_NAME = "/rover_status/battery_status"
|
||||
|
||||
COLOR_GREEN = "background-color: darkgreen; border: 1px solid black;"
|
||||
COLOR_ORANGE = "background-color: orange; border: 1px solid black;"
|
||||
COLOR_RED = "background-color: darkred; border: 1px solid black;"
|
||||
|
||||
|
||||
class SensorCore(QtCore.QThread):
|
||||
@@ -44,6 +49,9 @@ class SensorCore(QtCore.QThread):
|
||||
|
||||
frsky_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
|
||||
|
||||
battery_voltage_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
battery_voltage_stylesheet_change_ready__signal = QtCore.pyqtSignal(str)
|
||||
|
||||
def __init__(self, shared_objects):
|
||||
super(SensorCore, self).__init__()
|
||||
|
||||
@@ -72,6 +80,7 @@ class SensorCore(QtCore.QThread):
|
||||
self.ram = self.screen_main_window.ram # type: QtWidgets.QLabel
|
||||
self.gpu_temp = self.screen_main_window.gpu_temp # type: QtWidgets.QLabel
|
||||
self.emmc = self.screen_main_window.emmc # type: QtWidgets.QLabel
|
||||
self.battery = self.screen_main_window.battery_voltage_status_label # type: QtWidgets.QLabel
|
||||
|
||||
# ########## subscriptions pulling data from system_statuses_node.py ##########
|
||||
self.camera_status = rospy.Subscriber(CAMERA_TOPIC_NAME, CameraStatuses, self.__camera_callback)
|
||||
@@ -79,6 +88,7 @@ class SensorCore(QtCore.QThread):
|
||||
self.gps_status = rospy.Subscriber(GPS_TOPIC_NAME, GPSInfo, self.__gps_callback)
|
||||
self.jetson_status = rospy.Subscriber(JETSON_TOPIC_NAME, JetsonInfo, self.__jetson_callback)
|
||||
self.misc_status = rospy.Subscriber(MISC_TOPIC_NAME, MiscStatuses, self.__misc_callback)
|
||||
self.battery_status = rospy.Subscriber(BATTERY_TOPIC_NAME, BatteryStatusMessage, self.__battery_callback)
|
||||
|
||||
self.camera_msg = CameraStatuses()
|
||||
self.bogie_msg = BogieStatuses()
|
||||
@@ -86,6 +96,7 @@ class SensorCore(QtCore.QThread):
|
||||
self.GPS_msg = GPSInfo()
|
||||
self.jetson_msg = JetsonInfo()
|
||||
self.misc_msg = MiscStatuses()
|
||||
self.battery_msg = BatteryStatusMessage()
|
||||
|
||||
self.update_requester = rospy.Publisher(REQUEST_UPDATE_TOPIC, Empty, queue_size=10)
|
||||
|
||||
@@ -102,84 +113,84 @@ class SensorCore(QtCore.QThread):
|
||||
|
||||
if data.camera_zed is False:
|
||||
# self.zed.setStyleSheet("background-color: red;")
|
||||
self.camera_zed_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.camera_zed_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
# self.zed.setStyleSheet("background-color: darkgreen;")
|
||||
self.camera_zed_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
# self.zed.setStyleSheet(COLOR_GREEN)
|
||||
self.camera_zed_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
if data.camera_undercarriage is False:
|
||||
# self.under_cam.setStyleSheet("background-color: darkred;")
|
||||
self.camera_under_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
# self.under_cam.setStyleSheet(COLOR_RED)
|
||||
self.camera_under_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
# self.under_cam.setStyleSheet("background-color: darkgreen;")
|
||||
self.camera_under_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
# self.under_cam.setStyleSheet(COLOR_GREEN)
|
||||
self.camera_under_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
if data.camera_chassis is False:
|
||||
# self.chassis_cam.setStyleSheet("background-color: darkred;")
|
||||
self.camera_chassis_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
# self.chassis_cam.setStyleSheet(COLOR_RED)
|
||||
self.camera_chassis_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
# self.chassis_cam.setStyleSheet("background-color: darkgreen;")
|
||||
self.camera_chassis_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
# self.chassis_cam.setStyleSheet(COLOR_GREEN)
|
||||
self.camera_chassis_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
if data.camera_main_navigation is False:
|
||||
# self.main_cam.setStyleSheet("background-color: darkred;")
|
||||
self.camera_main_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
# self.main_cam.setStyleSheet(COLOR_RED)
|
||||
self.camera_main_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
# self.main_cam.setStyleSheet("background-color: darkgreen;")
|
||||
self.camera_main_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
# self.main_cam.setStyleSheet(COLOR_GREEN)
|
||||
self.camera_main_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
def __frsky_callback(self, data):
|
||||
self.FrSky_msg.FrSky_controller_connection_status = data.FrSky_controller_connection_status
|
||||
|
||||
if self.FrSky_msg.FrSky_controller_connection_status is False:
|
||||
self.frsky_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.frsky_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
self.frsky_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
self.frsky_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
def __jetson_callback(self, data):
|
||||
self.jetson_cpu_update_ready__signal.emit("TX2 CPU\n" + str(data.jetson_CPU) + "%")
|
||||
|
||||
if data.jetson_CPU > 85:
|
||||
self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||
self.jetson_cpu_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
|
||||
elif data.jetson_CPU > 95:
|
||||
self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.jetson_cpu_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
self.jetson_cpu_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
self.jetson_cpu_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
self.jetson_ram_update_ready__signal.emit("TX2 RAM\n" + str(data.jetson_RAM) + "%")
|
||||
|
||||
if data.jetson_RAM > 79:
|
||||
self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||
self.jetson_ram_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
|
||||
elif data.jetson_RAM > 89:
|
||||
self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.jetson_ram_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
self.jetson_ram_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
self.jetson_ram_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
self.jetson_gpu_temp_update_ready__signal.emit("TX2 TEMP\n" + str(data.jetson_GPU_temp) + "°C")
|
||||
|
||||
if data.jetson_GPU_temp > 64:
|
||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
|
||||
elif data.jetson_GPU_temp > 79:
|
||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
self.jetson_gpu_temp_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
self.jetson_emmc_update_ready__signal.emit("TX2 EMMC\n" + str(data.jetson_EMMC) + "%")
|
||||
|
||||
if data.jetson_EMMC > 79:
|
||||
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: orange;")
|
||||
self.jetson_emmc_stylesheet_change_ready__signal.emit(COLOR_ORANGE)
|
||||
elif data.jetson_EMMC > 89:
|
||||
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.jetson_emmc_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
self.jetson_emmc_stylesheet_change_ready__signal.emit("background-color: darkgreen")
|
||||
self.jetson_emmc_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
def __gps_callback(self, data):
|
||||
self.GPS_msg.UTC_GPS_time = data.UTC_GPS_time
|
||||
|
||||
if not data.GPS_connection_status:
|
||||
self.gps_stylesheet_change_ready__signal.emit("background-color: darkred;")
|
||||
self.gps_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
else:
|
||||
self.gps_stylesheet_change_ready__signal.emit("background-color: darkgreen;")
|
||||
self.gps_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
|
||||
def __misc_callback(self, data):
|
||||
self.misc_msg.arm_connection_status = data.arm_connection_status
|
||||
@@ -188,6 +199,16 @@ class SensorCore(QtCore.QThread):
|
||||
self.misc_msg.tower_connection_status = data.tower_connection_status
|
||||
self.misc_msg.chassis_pan_tilt_connection_status = data.chassis_pan_tilt_connection_status
|
||||
|
||||
def __battery_callback(self, data):
|
||||
voltage = data.battery_voltage / 1000.0
|
||||
|
||||
if voltage >= 20:
|
||||
self.battery_voltage_stylesheet_change_ready__signal.emit(COLOR_GREEN)
|
||||
else:
|
||||
self.battery_voltage_stylesheet_change_ready__signal.emit(COLOR_RED)
|
||||
|
||||
self.battery_voltage_update_ready__signal.emit("Battery Voltage\n" + str(voltage) + "V")
|
||||
|
||||
def __display_time(self):
|
||||
time = QtCore.QTime.currentTime()
|
||||
temp = time.toString('hh:mm')
|
||||
@@ -215,6 +236,9 @@ class SensorCore(QtCore.QThread):
|
||||
self.gps_stylesheet_change_ready__signal.connect(self.gps.setStyleSheet)
|
||||
self.frsky_stylesheet_change_ready__signal.connect(self.frsky.setStyleSheet)
|
||||
|
||||
self.battery_voltage_update_ready__signal.connect(self.battery.setText)
|
||||
self.battery_voltage_stylesheet_change_ready__signal.connect(self.battery.setStyleSheet)
|
||||
|
||||
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
|
||||
start_signal.connect(self.start)
|
||||
signals_and_slots_signal.connect(self.connect_signals_and_slots)
|
||||
|
||||
@@ -0,0 +1,126 @@
|
||||
# coding=utf-8
|
||||
#####################################
|
||||
# Imports
|
||||
#####################################
|
||||
# Python native imports
|
||||
from PyQt5 import QtCore, QtWidgets
|
||||
import logging
|
||||
from time import time
|
||||
import paramiko
|
||||
from pprint import pprint
|
||||
import json
|
||||
|
||||
#####################################
|
||||
# Global Variables
|
||||
#####################################
|
||||
THREAD_HERTZ = 2
|
||||
|
||||
ACCESS_POINT_IP = "192.168.1.20" # The channel only has to be set on the access point. The staion will adjust.
|
||||
ACCESS_POINT_USER = "ubnt"
|
||||
ACCESS_POINT_PASSWORD = "rover4lyfe^" # We don't care about this password, don't freak out. Wifi is open anyways...
|
||||
|
||||
GENERAL_WIRELESS_INFO_COMMAND = "wstalist"
|
||||
|
||||
|
||||
#####################################
|
||||
# UbiquitiRadioSettings Class Definition
|
||||
#####################################
|
||||
class UbiquitiStatus(QtCore.QThread):
|
||||
connection_quality_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
successful_transmission_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
radio_rates_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
radio_latency_update_ready__signal = QtCore.pyqtSignal(str)
|
||||
|
||||
def __init__(self, shared_objects):
|
||||
super(UbiquitiStatus, self).__init__()
|
||||
|
||||
# ########## Reference to class init variables ##########
|
||||
self.shared_objects = shared_objects
|
||||
self.left_screen = self.shared_objects["screens"]["left_screen"]
|
||||
|
||||
self.connection_quality_label = self.left_screen.connection_quality_label
|
||||
self.successful_transmit_label = self.left_screen.successful_transmit_label
|
||||
self.radio_rates_label = self.left_screen.radio_rates_label
|
||||
self.radio_latency_label = self.left_screen.radio_latency_label
|
||||
|
||||
# ########## Get the settings instance ##########
|
||||
self.settings = QtCore.QSettings()
|
||||
|
||||
# ########## Get the Pick And Plate instance of the logger ##########
|
||||
self.logger = logging.getLogger("groundstation")
|
||||
|
||||
# ########## Thread Flags ##########
|
||||
self.run_thread_flag = True
|
||||
|
||||
# ########## Class Variables ##########
|
||||
self.wait_time = 1.0 / THREAD_HERTZ
|
||||
|
||||
self.ssh_client = None
|
||||
|
||||
def run(self):
|
||||
try:
|
||||
self.setup_and_connect_ssh_client()
|
||||
except Exception:
|
||||
return
|
||||
|
||||
while self.run_thread_flag:
|
||||
start_time = time()
|
||||
|
||||
try:
|
||||
self.get_and_show_ubiquiti_status()
|
||||
except Exception, e:
|
||||
print e
|
||||
|
||||
time_diff = time() - start_time
|
||||
|
||||
self.msleep(max(int((self.wait_time - time_diff) * 1000), 0))
|
||||
|
||||
def setup_and_connect_ssh_client(self):
|
||||
self.ssh_client = paramiko.SSHClient()
|
||||
self.ssh_client.set_missing_host_key_policy(paramiko.AutoAddPolicy())
|
||||
self.ssh_client.connect(ACCESS_POINT_IP, username=ACCESS_POINT_USER, password=ACCESS_POINT_PASSWORD,
|
||||
compress=True)
|
||||
|
||||
def get_and_show_ubiquiti_status(self):
|
||||
ssh_stdin, ssh_stdout, ssh_stderr = self.ssh_client.exec_command(GENERAL_WIRELESS_INFO_COMMAND)
|
||||
|
||||
try:
|
||||
output_json = json.loads(ssh_stdout.read())[0]
|
||||
|
||||
transmit_percent = output_json["ccq"]
|
||||
quality = output_json["airmax"]["quality"]
|
||||
# capacity = output_json["airmax"]["capacity"]
|
||||
rx_rate = output_json["rx"]
|
||||
tx_rate = output_json["tx"]
|
||||
ground_tx_latency = output_json["tx_latency"]
|
||||
rover_tx_latency = output_json["remote"]["tx_latency"]
|
||||
|
||||
except IndexError:
|
||||
transmit_percent = 0
|
||||
quality = 0
|
||||
# capacity = output_json["airmax"]["capacity"]
|
||||
rx_rate = 0
|
||||
tx_rate = 0
|
||||
ground_tx_latency = "----"
|
||||
rover_tx_latency = "----"
|
||||
|
||||
|
||||
self.connection_quality_update_ready__signal.emit("Connection Quality\n%s %%" % quality)
|
||||
self.successful_transmission_update_ready__signal.emit("Successful Transmit\n%s %%" % transmit_percent)
|
||||
self.radio_rates_update_ready__signal.emit("TX Rate: %s Mbps\nRX Rate: %s Mbps" % (tx_rate, rx_rate))
|
||||
self.radio_latency_update_ready__signal.emit(
|
||||
"TX Latency: %s ms\nRX Latency: %s ms" % (ground_tx_latency, rover_tx_latency))
|
||||
|
||||
def connect_signals_and_slots(self):
|
||||
self.connection_quality_update_ready__signal.connect(self.connection_quality_label.setText)
|
||||
self.successful_transmission_update_ready__signal.connect(self.successful_transmit_label.setText)
|
||||
self.radio_rates_update_ready__signal.connect(self.radio_rates_label.setText)
|
||||
self.radio_latency_update_ready__signal.connect(self.radio_latency_label.setText)
|
||||
|
||||
def setup_signals(self, start_signal, signals_and_slots_signal, kill_signal):
|
||||
start_signal.connect(self.start)
|
||||
signals_and_slots_signal.connect(self.connect_signals_and_slots)
|
||||
kill_signal.connect(self.on_kill_threads_requested__slot)
|
||||
|
||||
def on_kill_threads_requested__slot(self):
|
||||
self.run_thread_flag = False
|
||||
@@ -251,23 +251,17 @@
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item row="1" column="2">
|
||||
<widget class="QLabel" name="ram">
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: darkred;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">TX2 RAM</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="4">
|
||||
<item row="5" column="4">
|
||||
<widget class="QLabel" name="emmc">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">TX2 EMMC</span></p></body></html></string>
|
||||
@@ -277,7 +271,7 @@
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="5">
|
||||
<item row="13" column="5">
|
||||
<widget class="QLabel" name="chassis_cam">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -311,7 +305,7 @@
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Chassis Camera
|
||||
@@ -322,7 +316,7 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="4">
|
||||
<item row="13" column="4">
|
||||
<widget class="QLabel" name="under_cam">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -356,7 +350,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Undercarriage Camera
|
||||
@@ -395,7 +389,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -443,7 +437,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>FrSky
|
||||
@@ -485,7 +479,7 @@ Connected</string>
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>3D Nav Mouse
|
||||
@@ -524,7 +518,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -538,7 +532,7 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="2">
|
||||
<item row="13" column="2">
|
||||
<widget class="QLabel" name="main_cam">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -566,7 +560,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -580,7 +574,7 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="1">
|
||||
<item row="8" column="1">
|
||||
<widget class="QLabel" name="gps">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -611,7 +605,7 @@ Connected</string>
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>GPS
|
||||
@@ -622,7 +616,7 @@ Fix</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="4">
|
||||
<item row="8" column="4">
|
||||
<widget class="QLabel" name="middle_left_wheel_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -653,18 +647,18 @@ Fix</string>
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Middle Left Wheel
|
||||
Disconnected</string>
|
||||
Connected</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="5">
|
||||
<item row="8" column="5">
|
||||
<widget class="QLabel" name="rear_left_wheel_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -692,7 +686,7 @@ Disconnected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -706,7 +700,7 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="4" column="2">
|
||||
<item row="8" column="2">
|
||||
<widget class="QLabel" name="front_left_wheel_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -734,7 +728,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -748,7 +742,7 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="9" column="1">
|
||||
<item row="13" column="1">
|
||||
<widget class="QLabel" name="zed">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -776,7 +770,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -790,10 +784,17 @@ Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="1">
|
||||
<item row="5" column="1">
|
||||
<widget class="QLabel" name="cpu">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">TX2 CPU</span></p></body></html></string>
|
||||
@@ -803,10 +804,17 @@ Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="1" column="5">
|
||||
<item row="5" column="5">
|
||||
<widget class="QLabel" name="gpu_temp">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color: darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p align="center"><span style=" font-size:9pt; font-weight:600;">TX2 TEMP</span></p></body></html></string>
|
||||
@@ -816,7 +824,7 @@ Disconnected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="2">
|
||||
<item row="10" column="2">
|
||||
<widget class="QLabel" name="front_right_wheel_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -844,7 +852,7 @@ Disconnected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -858,7 +866,7 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="1">
|
||||
<item row="10" column="1">
|
||||
<widget class="QLabel" name="battery_voltage_status_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -886,7 +894,7 @@ Connected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -900,7 +908,7 @@ N/A</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="4">
|
||||
<item row="10" column="4">
|
||||
<widget class="QLabel" name="middle_right_wheel_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -928,21 +936,41 @@ N/A</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkred;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Middle Right Wheel
|
||||
Disconnected</string>
|
||||
Connected</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="6" column="5">
|
||||
<item row="5" column="2">
|
||||
<widget class="QLabel" name="ram">
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p align="center"><span style=" font-weight:600;">TX2 RAM</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="10" column="5">
|
||||
<widget class="QLabel" name="rear_right_wheel_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
@@ -970,7 +998,7 @@ Disconnected</string>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen;</string>
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
@@ -984,6 +1012,174 @@ Connected</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="1">
|
||||
<widget class="QLabel" name="connection_quality_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>9999999</width>
|
||||
<height>9999999</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Connection Quality
|
||||
0.0%</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="4">
|
||||
<widget class="QLabel" name="radio_rates_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>9999999</width>
|
||||
<height>9999999</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>RX Rate: 240.0 Mbps
|
||||
TX Rate: 300 Mbps</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="2">
|
||||
<widget class="QLabel" name="successful_transmit_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>9999999</width>
|
||||
<height>9999999</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Successful Transmit
|
||||
0.0%</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item row="2" column="5">
|
||||
<widget class="QLabel" name="radio_latency_label">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>0</width>
|
||||
<height>0</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>9999999</width>
|
||||
<height>9999999</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>9</pointsize>
|
||||
<weight>75</weight>
|
||||
<bold>true</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">background-color:darkgreen; border: 0.5px solid black;</string>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>TX Latency: 10000 ms
|
||||
RX Latency: 10000 ms</string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
|
||||
@@ -20,6 +20,7 @@ import Framework.NavigationSystems.SpeedAndHeadingIndication as SpeedAndHeading
|
||||
import Framework.NavigationSystems.WaypointsCoordinator as WaypointsCoordinator
|
||||
import Framework.ArmSystems.ArmIndication as ArmIndication
|
||||
import Framework.StatusSystems.StatusCore as StatusCore
|
||||
import Framework.StatusSystems.UbiquitiStatusCore as UbiquitiStatusCore
|
||||
import Framework.SettingsSystems.UbiquitiRadioSettings as UbiquitiRadioSettings
|
||||
import Framework.InputSystems.SpaceNavControlSender as SpaceNavControlSender
|
||||
|
||||
@@ -108,6 +109,7 @@ class GroundStation(QtCore.QObject):
|
||||
self.__add_thread("Speed and Heading", SpeedAndHeading.SpeedAndHeadingIndication(self.shared_objects))
|
||||
self.__add_thread("Arm Indication", ArmIndication.ArmIndication(self.shared_objects))
|
||||
self.__add_thread("Rover Status", StatusCore.SensorCore(self.shared_objects))
|
||||
self.__add_thread("Ubiquiti Status", UbiquitiStatusCore.UbiquitiStatus(self.shared_objects))
|
||||
self.__add_thread("Ubiquiti Radio Settings", UbiquitiRadioSettings.UbiquitiRadioSettings(self.shared_objects))
|
||||
self.__add_thread("Waypoints Coordinator", WaypointsCoordinator.WaypointsCoordinator(self.shared_objects))
|
||||
self.__add_thread("Spacenav Sender", SpaceNavControlSender.SpaceNavControlSender(self.shared_objects))
|
||||
|
||||
@@ -71,7 +71,6 @@ class DriveCoordinator(object):
|
||||
self.left_bogie_publisher = rospy.Publisher(self.left_bogie_topic, DriveControlMessage, queue_size=1)
|
||||
self.right_bogie_publisher = rospy.Publisher(self.right_bogie_topic, DriveControlMessage, queue_size=1)
|
||||
|
||||
|
||||
self.last_message_time = time()
|
||||
|
||||
# ########## Run the Class ##########
|
||||
|
||||
@@ -34,7 +34,7 @@ COMMUNICATIONS_TIMEOUT = 0.01 # Seconds
|
||||
RX_DELAY = 0.01
|
||||
TX_DELAY = 0.01
|
||||
|
||||
DEFAULT_HERTZ = 20
|
||||
DEFAULT_HERTZ = 30
|
||||
|
||||
MODBUS_REGISTERS = {
|
||||
"DIRECTION": 0,
|
||||
|
||||
@@ -31,6 +31,6 @@
|
||||
<param name="second_motor_id" value="1"/>
|
||||
</node>
|
||||
|
||||
<node name="drive_coordinator" pkg="rover_control" type="drive_coordinator.py" output="screen"/>
|
||||
<node name="drive_coordinator" pkg="rover_control" type="drive_coordinator.py" respawn="true" output="screen"/>
|
||||
</group>
|
||||
</launch>
|
||||
|
||||
@@ -3,6 +3,9 @@
|
||||
<!-- https://answers.ros.org/question/241222/fusing-imu-gps-with-robot_location-package/ -->
|
||||
|
||||
<group ns="odometry">
|
||||
<!-- ########## Processes GPS and IMU Messages ########## -->
|
||||
<node name="odom_record" pkg="rosbag" type="record" args="-o /home/nvidia/BAGS/odometry /odometry/gps/fix /odometry/gps/sentence /odometry/imu/data /odometry/odometry/filtered /odometry/odometry/gps /odometry/vel" output="screen" />
|
||||
|
||||
<!-- ########## Processes GPS and IMU Messages ########## -->
|
||||
<node name="gps_and_imu" pkg="rover_odometry" type="odometry.py" respawn="true" output="screen" />
|
||||
|
||||
|
||||
@@ -0,0 +1,68 @@
|
||||
<launch>
|
||||
<!-- https://github.com/vikiboy/AGV_Localization/blob/master/robot_localization/launch/ekf.launch -->
|
||||
<!-- https://answers.ros.org/question/241222/fusing-imu-gps-with-robot_location-package/ -->
|
||||
<!-- ########## Processes GPS and IMU Messages ########## -->
|
||||
<node name="gps_and_imu" pkg="rover_odometry" type="odometry.py" respawn="true" output="screen" >
|
||||
<param name="gps_sentence_topic" value="/nmea_sentence"/>
|
||||
<param name="imu_data_topic" value="/imu/data"/>
|
||||
<!--<remap from="nmea_sentence" to="gps/sentence"/>-->
|
||||
<!--<remap from="imu/data" to="/imu/data"/>-->
|
||||
</node>
|
||||
<!-- ########## Converts GPS Sentences to GPS Fix data ########## -->
|
||||
<node name="navsat_driver" pkg="nmea_navsat_driver" type="nmea_topic_driver" output="screen">
|
||||
<remap from="nmea_sentence" to="gps/sentence"/>
|
||||
</node>
|
||||
|
||||
<node pkg="tf" type="static_transform_publisher" name="imu_tf" args="0 0 0 0 0 0 1 base_link imu 20"/>
|
||||
<node pkg="tf" type="static_transform_publisher" name="gps_tf" args="0 0 0 0 0 0 1 base_link gps 20"/>
|
||||
|
||||
<node pkg="robot_localization" type="ekf_localization_node" name="ekf_localization" clear_params="true">
|
||||
<param name="output_frame" value="odom"/>
|
||||
<param name="frequency" value="20"/>
|
||||
<param name="odom_used" value="true"/>
|
||||
<param name="imu_used" value="true"/>
|
||||
<param name="vo_used" value="false"/>
|
||||
<param name="sensor_timeout" value="0.1"/>
|
||||
<param name="two_d_mode" value="false"/>
|
||||
|
||||
<param name="map_frame" value="map"/>
|
||||
<param name="odom_frame" value="odom"/>
|
||||
<param name="base_link_frame" value="base_link"/>
|
||||
<param name="world_frame" value="odom"/>
|
||||
|
||||
<param name="odom0" value="/odometry/gps"/>
|
||||
<param name="imu0" value="/imu/data"/>
|
||||
|
||||
<rosparam param="odom0_config">[true, true, false,
|
||||
false, false, false,
|
||||
false , false, false,
|
||||
false, false, false,
|
||||
false, false, false]</rosparam>
|
||||
|
||||
<rosparam param="imu0_config">[false, false, false,
|
||||
true , true , true,
|
||||
false, false, false,
|
||||
true , true , true ,
|
||||
true , true , true ]</rosparam>
|
||||
|
||||
<param name="odom0_differential" value="false"/>
|
||||
<param name="imu0_differential" value="false"/>
|
||||
|
||||
<param name="imu0_remove_gravitational_acceleration" value="true"/>
|
||||
|
||||
<param name="odom0_relative" value="false"/>
|
||||
<param name="imu0_relative" value="false"/>
|
||||
|
||||
<param name="print_diagnostics" value="true"/>
|
||||
|
||||
<!-- ======== ADVANCED PARAMETERS ======== -->
|
||||
|
||||
<param name="odom0_queue_size" value="2"/>
|
||||
<param name="imu0_queue_size" value="10"/>
|
||||
|
||||
</node>
|
||||
|
||||
<node name="navsat_transform" pkg="robot_localization" type="navsat_transform_node" output="screen">
|
||||
<param name="broadcast_utm_transform" value="true"/>
|
||||
</node>
|
||||
</launch>
|
||||
@@ -36,7 +36,7 @@ DEFAULT_IRIS_STATUS_TOPIC_NAME = "/rover_control/iris_status"
|
||||
DEFAULT_BOGIE_LEFT_TOPIC_NAME = '/rover_control/drive_status/left'
|
||||
DEFAULT_BOGIE_RIGHT_TOPIC_NAME = '/rover_control/drive_status/right'
|
||||
DEFAULT_BOGIE_REAR_TOPIC_NAME = '/rover_control/drive_status/rear'
|
||||
DEFAULT_GPS_NMEA_TOPIC_NAME = '/nmea_sentence'
|
||||
DEFAULT_GPS_NMEA_TOPIC_NAME = '/odometry/gps/sentence'
|
||||
|
||||
|
||||
#####################################
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
import paramiko
|
||||
import json
|
||||
from pprint import pprint
|
||||
import time
|
||||
|
||||
# ath0 21 channels in total; available frequencies :
|
||||
# Channel 01 : 2.412 GHz
|
||||
@@ -43,12 +43,25 @@ ssh.set_missing_host_key_policy(paramiko.AutoAddPolicy)
|
||||
# Before anyone complains, I'm not worried about this password being online.
|
||||
# We only set one because the web interfaces HAVE to have one
|
||||
ssh.connect("192.168.1.20", username="ubnt", password="rover4lyfe^", compress=True)
|
||||
|
||||
while True:
|
||||
ssh_stdin, ssh_stdout, ssh_stderr = ssh.exec_command(get_general_info)
|
||||
|
||||
pprint( json.loads(ssh_stdout.read()) )
|
||||
output_json = json.loads(ssh_stdout.read())[0]
|
||||
|
||||
ssh_stdin, ssh_stdout, ssh_stderr = ssh.exec_command(set_wireless_frequency)
|
||||
ssh_stdin, ssh_stdout, ssh_stderr = ssh.exec_command(get_wireless_info)
|
||||
successful_transmit_percent = output_json["ccq"]
|
||||
quality = output_json["airmax"]["quality"]
|
||||
capacity = output_json["airmax"]["capacity"]
|
||||
rx_rate = output_json["rx"]
|
||||
tx_rate = output_json["tx"]
|
||||
ground_tx_latency = output_json["tx_latency"]
|
||||
rover_tx_latency = output_json["remote"]["tx_latency"]
|
||||
|
||||
print successful_transmit_percent, " | ", quality, " | ", capacity, " | ", rx_rate, " | ", tx_rate, " | ", ground_tx_latency, " | ", rover_tx_latency
|
||||
|
||||
time.sleep(0.25)
|
||||
# ssh_stdin, ssh_stdout, ssh_stderr = ssh.exec_command(set_wireless_frequency)
|
||||
# ssh_stdin, ssh_stdout, ssh_stderr = ssh.exec_command(get_wireless_info)
|
||||
#
|
||||
# print ssh_stdout.read()
|
||||
|
||||
print ssh_stdout.read()
|
||||
Reference in New Issue
Block a user