Skip to content

Commit

Permalink
updated navigator_gui to ROS2
Browse files Browse the repository at this point in the history
  • Loading branch information
anvitD authored and anvitD committed Apr 18, 2024
1 parent 66e926e commit 128e797
Show file tree
Hide file tree
Showing 4 changed files with 33 additions and 24 deletions.
22 changes: 13 additions & 9 deletions NaviGator/utils/navigator_gui/navigator_gui/dashboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@
from copy import copy
from typing import Any

import rclpy
import rospkg
import rospy
from mil_tools import thread_lock
from navigator_msgs.msg import Host, Hosts
from python_qt_binding import QtCore, QtWidgets, loadUi
Expand Down Expand Up @@ -79,7 +79,7 @@ def __init__(self, context: Any):

@thread_lock(lock)
def update_gui(self):
self.system_time["current"] = rospy.Time.now()
self.system_time["current"] = rclpy.Time.now()
if self.system_time["current"] != self.system_time["displayed"]:
self.update_system_time_status()
if self.kill_status["current"] != self.kill_status["displayed"]:
Expand Down Expand Up @@ -204,18 +204,22 @@ def connect_ros(self) -> None:
within this class.
"""
# Attempts to read the battery voltage parameters (sets them to defaults if they have not been set)
self.battery_low_voltage = rospy.get_param(
self.battery_low_voltage = self.declare_parameter(
"/battery_monitor/battery_low_voltage",
24,
)
self.battery_critical_voltage = rospy.get_param(
self.battery_critical_voltage = self.get_parameter(
"/battery_monitor/battery_critical_voltage",
20,
)

rospy.Subscriber("/wrench/selected", String, self.cache_operating_mode)
rospy.Subscriber("/battery_monitor", Float32, self.cache_battery_voltage)
rospy.Subscriber("/host_monitor", Hosts, self.cache_hosts)
self.create_subscription(String, "/wrench/selected", self.cache_operating_mode)
self.create_subscription(
Float32,
"/battery_monitor",
self.cache_battery_voltage,
)
self.create_subscription(Hosts, "/host_monitor", self.cache_hosts)

self.kill_listener = AlarmListener(
"kill",
Expand All @@ -241,7 +245,7 @@ def cache_hosts(self, msg: Hosts) -> None:
in the hosts receiving variable.
"""
self.hosts["current"] = msg
self.hosts["stamp"] = rospy.Time.now()
self.hosts["stamp"] = rclpy.Time.now()

def update_kill_status(self) -> None:
if self.kill_status["current"] is False:
Expand Down Expand Up @@ -291,7 +295,7 @@ def monitor_battery_voltage(self) -> None:

# Sets the battery voltage to 'Unknown' if no message has been current in 15s
if (
(rospy.Time.now() - self.battery_voltage["stamp"]) > rospy.Duration(15)
(rclpy.Time.now() - self.battery_voltage["stamp"]) > rclpy.Duration(15)
) or (self.battery_voltage["current"] is None):
self.battery_voltage["current"] = "Unknown"

Expand Down
18 changes: 10 additions & 8 deletions NaviGator/utils/navigator_gui/navigator_gui/host_monitor.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,8 +6,9 @@

import socket
import subprocess
import sys

import rospy
import rclpy
from navigator_msgs.msg import Host, Hosts

__author__ = "Anthony Olive"
Expand All @@ -17,15 +18,16 @@
__license__ = "MIT"


rospy.init_node("host_monitor")
rclpy.init(args=sys.argv)
node = rclpy.create_node("host_monitor")


class HostMonitor:
def __init__(self):
self.pub_hosts = rospy.Publisher(
"/host_monitor",
self.pub_hosts = self.create_publisher(
Hosts,
queue_size=1,
"/host_monitor",
1,
latch=True,
)
self.hosts = Hosts()
Expand Down Expand Up @@ -61,7 +63,7 @@ def check_hosts(self) -> None:

self.hosts.hosts.append(host)

def publish(self, _: rospy.timer.TimerEvent) -> None:
def publish(self, _: rclpy.timer.TimerEvent) -> None:
"""
Publishes the list of hosts and the information gathered about them.
"""
Expand All @@ -71,5 +73,5 @@ def publish(self, _: rospy.timer.TimerEvent) -> None:

if __name__ == "__main__":
monitor = HostMonitor()
rospy.Timer(rospy.Duration(10), monitor.publish, oneshot=False)
rospy.spin()
rclpy.Timer(rclpy.Duration(10), monitor.publish, oneshot=False)
rclpy.spin()
10 changes: 5 additions & 5 deletions NaviGator/utils/navigator_gui/navigator_gui/shooter.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,8 @@

import os

import rclpy
import rospkg
import rospy
from python_qt_binding import QtCore, QtWidgets, loadUi
from qt_gui.plugin import Plugin
from remote_control_lib import RemoteControl
Expand Down Expand Up @@ -44,15 +44,15 @@ def __init__(self, context):

self.shooter_status = {
"received": "Unknown",
"stamp": rospy.Time.now(),
"stamp": rclpy.Time.now(),
"cached": "Unknown",
}

self.disc_speed_setting = 0

self.connect_ui()

rospy.Subscriber("/shooter/status", String, self.cache_shooter_status)
self.create_subscription(String, "/shooter/status", self.cache_shooter_status)

# Deals with problem of multiple instances of same plugin
if context.serial_number() > 1:
Expand Down Expand Up @@ -142,15 +142,15 @@ def cache_shooter_status(self, msg: String) -> None:
Stores the shooter status when it is published.
"""
self.shooter_status["received"] = msg.data
self.shooter_status["stamp"] = rospy.Time.now()
self.shooter_status["stamp"] = rclpy.Time.now()

def monitor_shooter_status(self) -> None:
"""
Monitors the shooter status on a 1s interval. Only updates the display
when the received shooter status has changed. The connection to the
status will time out if no message has been received in 1s.
"""
if (rospy.Time.now() - self.shooter_status["stamp"]) < rospy.Duration(1):
if (rclpy.Time.now() - self.shooter_status["stamp"]) < rclpy.Duration(1):
self.remote.is_timed_out = False

# Sets the remote control to timed out and the shooter status to 'Unknown' if no message has been received in 1s
Expand Down
7 changes: 5 additions & 2 deletions NaviGator/utils/navigator_gui/navigator_gui/stc_display.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
import os

import rospkg
import rospy
from navigator_msgs.msg import ScanTheCode
from python_qt_binding import QtWidgets, loadUi
from python_qt_binding.QtWidgets import QWidget
Expand Down Expand Up @@ -63,7 +62,11 @@ def __init__(self, context):
# Add widget to the user interface
context.add_widget(self._widget)
self.connect_ui()
self.stc_sub = rospy.Subscriber(self.STC_TOPIC, ScanTheCode, self.update_gui)
self.stc_sub = self.create_subscription(
ScanTheCode,
self.STC_TOPIC,
self.update_gui,
)

def connect_ui(self) -> None:
self.color1_rect = self._widget.findChild(QtWidgets.QColumnView, "color1_rect")
Expand Down

0 comments on commit 128e797

Please sign in to comment.