mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-08 18:21:15 +00:00
system_statuses_node.py is updated so it handles 6 message types: GPSInfo.msg, JetsonInfo.msg, FrSkyStatus.msg, MiscStatuses.msg, BogieStatuses.msg, and CameraStatuses.msg instead of 1 giant message.
This commit is contained in:
@@ -57,7 +57,12 @@ find_package(catkin REQUIRED COMPONENTS
|
||||
add_message_files(
|
||||
FILES
|
||||
RoverSysStatus.msg
|
||||
Camera2Changer.msg
|
||||
BogieStatuses.msg
|
||||
FrSkyStatus.msg
|
||||
JetsonInfo.msg
|
||||
CameraStatuses.msg
|
||||
GPSInfo.msg
|
||||
MiscStatuses.msg
|
||||
)
|
||||
|
||||
## Generate services in the 'srv' folder
|
||||
|
||||
BIN
rover/system_statuses/msg/.RoverSysStatus.msg.kate-swp
Normal file
BIN
rover/system_statuses/msg/.RoverSysStatus.msg.kate-swp
Normal file
Binary file not shown.
3
rover/system_statuses/msg/BogieStatuses.msg
Normal file
3
rover/system_statuses/msg/BogieStatuses.msg
Normal file
@@ -0,0 +1,3 @@
|
||||
int8 bogie_connection_1
|
||||
int8 bogie_connection_2
|
||||
int8 bogie_connection_3
|
||||
@@ -1 +0,0 @@
|
||||
int8 camera_2_value
|
||||
4
rover/system_statuses/msg/CameraStatuses.msg
Normal file
4
rover/system_statuses/msg/CameraStatuses.msg
Normal file
@@ -0,0 +1,4 @@
|
||||
int8 camera_zed
|
||||
int8 camera_undercarriage
|
||||
int8 camera_chassis
|
||||
int8 camera_main_navigation
|
||||
1
rover/system_statuses/msg/FrSkyStatus.msg
Normal file
1
rover/system_statuses/msg/FrSkyStatus.msg
Normal file
@@ -0,0 +1 @@
|
||||
int8 FrSky_controller_connection_status
|
||||
2
rover/system_statuses/msg/GPSInfo.msg
Normal file
2
rover/system_statuses/msg/GPSInfo.msg
Normal file
@@ -0,0 +1,2 @@
|
||||
int8 UTC_GPS_time
|
||||
int8 GPS_connection_status
|
||||
4
rover/system_statuses/msg/JetsonInfo.msg
Normal file
4
rover/system_statuses/msg/JetsonInfo.msg
Normal file
@@ -0,0 +1,4 @@
|
||||
int8 jetson_CPU
|
||||
int8 jetson_RAM
|
||||
int8 jetson_EMMC
|
||||
int8 jetson_NVME_SSD
|
||||
5
rover/system_statuses/msg/MiscStatuses.msg
Normal file
5
rover/system_statuses/msg/MiscStatuses.msg
Normal file
@@ -0,0 +1,5 @@
|
||||
int8 arm_connection_status
|
||||
int8 arm_end_effector_connection_statuses
|
||||
int8 sample_containment_connection_status
|
||||
int8 tower_connection_status
|
||||
int8 chassis_pan_tilt_connection_status
|
||||
52
rover/system_statuses/scripts/.idea/workspace.xml
generated
52
rover/system_statuses/scripts/.idea/workspace.xml
generated
@@ -14,11 +14,9 @@
|
||||
<file leaf-file-name="system_statuses_node.py" pinned="false" current-in-tab="false">
|
||||
<entry file="file://$PROJECT_DIR$/system_statuses_node.py">
|
||||
<provider selected="true" editor-type-id="text-editor">
|
||||
<state relative-caret-position="-732">
|
||||
<caret line="17" column="63" lean-forward="false" selection-start-line="17" selection-start-column="36" selection-end-line="17" selection-end-column="63" />
|
||||
<folding>
|
||||
<element signature="e#22#43#0" expanded="true" />
|
||||
</folding>
|
||||
<state relative-caret-position="72">
|
||||
<caret line="3" column="32" lean-forward="false" selection-start-line="3" selection-start-column="32" selection-end-line="3" selection-end-column="32" />
|
||||
<folding />
|
||||
</state>
|
||||
</provider>
|
||||
</entry>
|
||||
@@ -26,22 +24,10 @@
|
||||
<file leaf-file-name="rover_statuses.py" pinned="false" current-in-tab="true">
|
||||
<entry file="file://$PROJECT_DIR$/rover_statuses.py">
|
||||
<provider selected="true" editor-type-id="text-editor">
|
||||
<state relative-caret-position="708">
|
||||
<caret line="43" column="40" lean-forward="false" selection-start-line="43" selection-start-column="40" selection-end-line="43" selection-end-column="40" />
|
||||
<state relative-caret-position="0">
|
||||
<caret line="0" column="4" lean-forward="false" selection-start-line="0" selection-start-column="4" selection-end-line="0" selection-end-column="4" />
|
||||
<folding>
|
||||
<element signature="e#22#43#0" expanded="true" />
|
||||
</folding>
|
||||
</state>
|
||||
</provider>
|
||||
</entry>
|
||||
</file>
|
||||
<file leaf-file-name="camera_2_updater.py" pinned="false" current-in-tab="false">
|
||||
<entry file="file://$PROJECT_DIR$/camera_2_updater.py">
|
||||
<provider selected="true" editor-type-id="text-editor">
|
||||
<state relative-caret-position="216">
|
||||
<caret line="9" column="33" lean-forward="false" selection-start-line="9" selection-start-column="33" selection-end-line="9" selection-end-column="33" />
|
||||
<folding>
|
||||
<element signature="e#23#35#0" expanded="true" />
|
||||
<element signature="e#22#34#0" expanded="true" />
|
||||
</folding>
|
||||
</state>
|
||||
</provider>
|
||||
@@ -59,11 +45,11 @@
|
||||
<component name="IdeDocumentHistory">
|
||||
<option name="CHANGED_PATHS">
|
||||
<list>
|
||||
<option value="$PROJECT_DIR$/camera_2_updater.py" />
|
||||
<option value="$PROJECT_DIR$/system_statuses.py" />
|
||||
<option value="$PROJECT_DIR$/node_statuses.py" />
|
||||
<option value="$PROJECT_DIR$/system_statuses_node.py" />
|
||||
<option value="$PROJECT_DIR$/camera_2_updater.py" />
|
||||
<option value="$PROJECT_DIR$/rover_statuses.py" />
|
||||
<option value="$PROJECT_DIR$/system_statuses_node.py" />
|
||||
</list>
|
||||
</option>
|
||||
</component>
|
||||
@@ -192,30 +178,26 @@
|
||||
</entry>
|
||||
<entry file="file://$PROJECT_DIR$/camera_2_updater.py">
|
||||
<provider selected="true" editor-type-id="text-editor">
|
||||
<state relative-caret-position="216">
|
||||
<caret line="9" column="33" lean-forward="false" selection-start-line="9" selection-start-column="33" selection-end-line="9" selection-end-column="33" />
|
||||
<folding>
|
||||
<element signature="e#23#35#0" expanded="true" />
|
||||
</folding>
|
||||
<state relative-caret-position="192">
|
||||
<caret line="8" column="63" lean-forward="true" selection-start-line="8" selection-start-column="63" selection-end-line="8" selection-end-column="63" />
|
||||
<folding />
|
||||
</state>
|
||||
</provider>
|
||||
</entry>
|
||||
<entry file="file://$PROJECT_DIR$/system_statuses_node.py">
|
||||
<provider selected="true" editor-type-id="text-editor">
|
||||
<state relative-caret-position="-732">
|
||||
<caret line="17" column="63" lean-forward="false" selection-start-line="17" selection-start-column="36" selection-end-line="17" selection-end-column="63" />
|
||||
<folding>
|
||||
<element signature="e#22#43#0" expanded="true" />
|
||||
</folding>
|
||||
<state relative-caret-position="72">
|
||||
<caret line="3" column="32" lean-forward="false" selection-start-line="3" selection-start-column="32" selection-end-line="3" selection-end-column="32" />
|
||||
<folding />
|
||||
</state>
|
||||
</provider>
|
||||
</entry>
|
||||
<entry file="file://$PROJECT_DIR$/rover_statuses.py">
|
||||
<provider selected="true" editor-type-id="text-editor">
|
||||
<state relative-caret-position="708">
|
||||
<caret line="43" column="40" lean-forward="false" selection-start-line="43" selection-start-column="40" selection-end-line="43" selection-end-column="40" />
|
||||
<state relative-caret-position="0">
|
||||
<caret line="0" column="4" lean-forward="false" selection-start-line="0" selection-start-column="4" selection-end-line="0" selection-end-column="4" />
|
||||
<folding>
|
||||
<element signature="e#22#43#0" expanded="true" />
|
||||
<element signature="e#22#34#0" expanded="true" />
|
||||
</folding>
|
||||
</state>
|
||||
</provider>
|
||||
|
||||
@@ -1,26 +1,26 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
import rospy
|
||||
from system_statuses.msg import Camera2Changer
|
||||
# import rospy
|
||||
# from system_statuses.msg import Camera2Changer
|
||||
|
||||
|
||||
def camera_2_changer():
|
||||
pub = rospy.Publisher('camera_2_changer_chatter', Camera2Changer, queue_size=10)
|
||||
rospy.init_node('camera_2_changer_talker', anonymous=True)
|
||||
# r = rospy.sleep(10) # 10hz
|
||||
msg = Camera2Changer()
|
||||
msg.camera_2_value = 0
|
||||
# def camera_2_changer():
|
||||
# pub = rospy.Publisher('camera_2_changer_chatter', Camera2Changer, queue_size=10)
|
||||
# rospy.init_node('camera_2_changer_talker', anonymous=True)
|
||||
# # r = rospy.sleep(10) # 10hz
|
||||
# msg = Camera2Changer()
|
||||
# msg.camera_2_value = 0
|
||||
|
||||
while not rospy.is_shutdown():
|
||||
msg.camera_2_value = (msg.camera_2_value + 1) % 2
|
||||
rospy.loginfo(msg)
|
||||
pub.publish(msg)
|
||||
# while not rospy.is_shutdown():
|
||||
# msg.camera_2_value = (msg.camera_2_value + 1) % 2
|
||||
# rospy.loginfo(msg)
|
||||
# pub.publish(msg)
|
||||
# r.sleep()
|
||||
rospy.sleep(2.)
|
||||
## rospy.sleep(2.)
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
try:
|
||||
camera_2_changer()
|
||||
except rospy.ROSInterruptException:
|
||||
pass
|
||||
#if __name__ == '__main__':
|
||||
# try:
|
||||
# camera_2_changer()
|
||||
# except rospy.ROSInterruptException:
|
||||
# pass
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
#!/usr/bin/env python
|
||||
import rospy, os.path
|
||||
import rospy
|
||||
from system_statuses.msg import RoverSysStatus
|
||||
|
||||
|
||||
|
||||
@@ -1,11 +1,14 @@
|
||||
#!/usr/bin/env python
|
||||
import rospy, os.path
|
||||
from system_statuses.msg import RoverSysStatus, Camera2Changer
|
||||
import rospy
|
||||
import os.path
|
||||
from system_statuses.msg import CameraStatuses, BogieStatuses, FrSkyStatus, GPSInfo, MiscStatuses, JetsonInfo
|
||||
|
||||
|
||||
|
||||
class SystemStatuses:
|
||||
|
||||
def __init__(self):
|
||||
# Camera path locations
|
||||
self.system_path_locations = [
|
||||
'/dev/rover/camera_zed',
|
||||
'/dev/rover/camera_undercarriage',
|
||||
@@ -15,28 +18,26 @@ class SystemStatuses:
|
||||
|
||||
rospy.init_node('SystemStatuses')
|
||||
|
||||
self.pub = rospy.Publisher('rover_system_status_chatter', RoverSysStatus, queue_size=10)
|
||||
# init all publisher functions
|
||||
self.pub_camera = rospy.Publisher('camera_system_status_chatter', CameraStatuses, queue_size=10)
|
||||
self.pub_bogie = rospy.Publisher('bogie_system_status_chatter', BogieStatuses, queue_size=10)
|
||||
self.pub_FrSky = rospy.Publisher('FrSky_system_status_chatter', FrSkyStatus, queue_size=10)
|
||||
self.pub_GPS = rospy.Publisher('GPS_system_status_chatter', GPSInfo, queue_size=10)
|
||||
self.pub_jetson = rospy.Publisher('jetson_system_status_chatter', JetsonInfo, queue_size=10)
|
||||
self.pub_Misc = rospy.Publisher('misc_system_status_chatter', MiscStatuses, queue_size=10)
|
||||
|
||||
# Test Subscription for updating camera_undercarriage
|
||||
rospy.Subscriber('camera_2_changer_chatter', Camera2Changer, self.__sub_callback)
|
||||
|
||||
self.msg = RoverSysStatus()
|
||||
# init all message variables
|
||||
self.camera_msg = CameraStatuses()
|
||||
self.bogie_msg = BogieStatuses()
|
||||
self.FrSky_msg = FrSkyStatus()
|
||||
self.GPS_msg = GPSInfo()
|
||||
self.jetson_msg = JetsonInfo()
|
||||
self.misc_msg = MiscStatuses()
|
||||
self.__set_msg_values()
|
||||
|
||||
# Simple Subscriber test boolean -- camera_2_updated.py
|
||||
# self.hasCameraUndercarriageChanged = False
|
||||
|
||||
# Callback for test Subscription of camera_2_updater.py -- checks if camera_undercarriage
|
||||
# has changed, updates value, and updates bool for run->pub.publish to execute
|
||||
def __sub_callback(self, data):
|
||||
rospy.loginfo("Camera_undercarriage Status Changed: %d " % data.camera_2_value)
|
||||
if self.msg.camera_undercarriage != data.camera_2_value:
|
||||
self.msg.camera_undercarriage = data.camera_2_value
|
||||
self.hasCameraUndercarriageChanged = True
|
||||
|
||||
# INIT all RoverSysMessage values
|
||||
def __set_msg_values(self):
|
||||
self.__utc_gps_time()
|
||||
self.__gps_update()
|
||||
self.__bogie_connection_statuses()
|
||||
self.__arm_connection_status()
|
||||
self.__arm_end_effector_connection_statuses()
|
||||
@@ -44,77 +45,98 @@ class SystemStatuses:
|
||||
self.__sample_containment_connection_status()
|
||||
self.__tower_connection_status()
|
||||
self.__chassis_pan_tilt_connection_status()
|
||||
self.__gps_connection_status()
|
||||
self.__jetson_usage_information()
|
||||
self.__frsky_controller_connection_status()
|
||||
|
||||
# Pulls the UTC GPS Time (WIP)
|
||||
def __utc_gps_time(self):
|
||||
self.msg.UTC_GPS_time = 0
|
||||
def __gps_update(self):
|
||||
self.GPS_msg.UTC_GPS_time = 0
|
||||
self.GPS_msg.GPS_connection_status = 0
|
||||
|
||||
# Pulls bogie connection statuses (WIP)
|
||||
def __bogie_connection_statuses(self):
|
||||
self.msg.bogie_connection_1 = 0
|
||||
self.msg.bogie_connection_2 = 0
|
||||
self.msg.bogie_connection_3 = 0
|
||||
self.bogie_msg.bogie_connection_1 = 0
|
||||
self.bogie_msg.bogie_connection_2 = 0
|
||||
self.bogie_msg.bogie_connection_3 = 0
|
||||
|
||||
# Checks arm connection status (WIP)
|
||||
def __arm_connection_status(self):
|
||||
self.msg.arm_connection_status = 0
|
||||
self.misc_msg.arm_connection_status = 0
|
||||
|
||||
# Checks Arm End Effector Connection Statuses (WIP)
|
||||
def __arm_end_effector_connection_statuses(self):
|
||||
self.msg.arm_end_effector_connection_statuses = 0
|
||||
self.misc_msg.arm_end_effector_connection_statuses = 0
|
||||
|
||||
# Sets the Camera values (zed, undercarriage, chassis, and main_nav
|
||||
def __set_cameras(self):
|
||||
# Check if camera_zed is found
|
||||
self.msg.camera_zed = 1 if os.path.exists(self.system_path_locations[0]) else 0
|
||||
self.camera_msg.camera_zed = 1 if os.path.exists(self.system_path_locations[0]) else 0
|
||||
# Check if camera_undercarriage is found
|
||||
self.msg.camera_undercarriage = 1 if os.path.exists(self.system_path_locations[1]) else 0
|
||||
self.camera_msg.camera_undercarriage = 1 if os.path.exists(self.system_path_locations[1]) else 0
|
||||
# Check if camera_chassis is found
|
||||
self.msg.camera_chassis = 1 if os.path.exists(self.system_path_locations[2]) else 0
|
||||
self.camera_msg.camera_chassis = 1 if os.path.exists(self.system_path_locations[2]) else 0
|
||||
# Check if camera_main_navigation is found
|
||||
self.msg.camera_main_navigation = 1 if os.path.exists(self.system_path_locations[3]) else 0
|
||||
self.camera_msg.camera_main_navigation = 1 if os.path.exists(self.system_path_locations[3]) else 0
|
||||
|
||||
# Checks Sample Containment Connection Status (WIP)
|
||||
def __sample_containment_connection_status(self):
|
||||
self.msg.sample_containment_connection_status = 0
|
||||
self.misc_msg.sample_containment_connection_status = 0
|
||||
|
||||
def __tower_connection_status(self):
|
||||
self.msg.tower_connection_status = 0
|
||||
self.misc_msg.tower_connection_status = 0
|
||||
|
||||
# Checks Tower Connection Status (WIP)
|
||||
def __chassis_pan_tilt_connection_status(self):
|
||||
self.msg.chassis_pan_tilt_connection_status = 0
|
||||
|
||||
# Checks GPS Status (WIP)
|
||||
def __gps_connection_status(self):
|
||||
self.msg.GPS_connection_status = 0
|
||||
self.misc_msg.chassis_pan_tilt_connection_status = 0
|
||||
|
||||
# Get Jetson Statuses (WIP)
|
||||
def __jetson_usage_information(self):
|
||||
self.msg.jetson_CPU = 0
|
||||
self.msg.jetson_RAM = 0
|
||||
self.msg.jetson_EMMC = 0
|
||||
self.msg.jetson_NVME_SSD = 0
|
||||
self.jetson_msg.jetson_CPU = 0
|
||||
self.jetson_msg.jetson_RAM = 0
|
||||
self.jetson_msg.jetson_EMMC = 0
|
||||
self.jetson_msg.jetson_NVME_SSD = 0
|
||||
|
||||
# Check FrSky Controller Connection Status (WIP)
|
||||
def __frsky_controller_connection_status(self):
|
||||
self.msg.FrSky_controller_connection_status = 0
|
||||
self.FrSky_msg.FrSky_controller_connection_status = 0
|
||||
|
||||
def run(self):
|
||||
r = rospy.Rate(10)
|
||||
# rospy.loginfo(self.msg)
|
||||
# self.pub.publish(self.msg)
|
||||
while not rospy.is_shutdown():
|
||||
if (self.msg.camera_zed != os.path.exists(self.system_path_locations[0]) or
|
||||
self.msg.camera_undercarriage != os.path.exists(self.system_path_locations[1]) or
|
||||
self.msg.camera_chassis != os.path.exists(self.system_path_locations[2]) or
|
||||
self.msg.camera_main_navigation != os.path.exists(self.system_path_locations[3])):
|
||||
# Camera Check & update if change
|
||||
if (self.camera_msg.camera_zed != os.path.exists(self.system_path_locations[0]) or
|
||||
self.camera_msg.camera_undercarriage != os.path.exists(self.system_path_locations[1]) or
|
||||
self.camera_msg.camera_chassis != os.path.exists(self.system_path_locations[2]) or
|
||||
self.camera_msg.camera_main_navigation != os.path.exists(self.system_path_locations[3])):
|
||||
self.__set_cameras()
|
||||
rospy.loginfo(self.msg)
|
||||
self.pub.publish(self.msg)
|
||||
self.pub_camera.publish(self.camera_msg)
|
||||
|
||||
# Placeholder Jetson Info Check
|
||||
if (self.jetson_msg.jetson_CPU != 0 or
|
||||
self.jetson_msg.jetson_RAM != 0 or
|
||||
self.jetson_msg.jetson_EMMC != 0 or
|
||||
self.jetson_msg.jetson_NVME_SSD != 0):
|
||||
self.__jetson_usage_information()
|
||||
self.pub_jetson.publish(self.jetson_msg)
|
||||
|
||||
# Placeholder FrSky Controller Check
|
||||
if self.FrSky_msg.FrSky_controller_connection_status != 0:
|
||||
self.__frsky_controller_connection_status()
|
||||
self.pub_FrSky.publish(self.FrSky_msg)
|
||||
|
||||
# Placeholder bogie status check
|
||||
if (self.bogie_msg.bogie_connection_1 != 0 or
|
||||
self.bogie_msg.bogie_connection_2 != 0 or
|
||||
self.bogie_msg.bogie_connection_3 != 0):
|
||||
self.__bogie_connection_statuses()
|
||||
self.pub_bogie.publish(self.bogie_msg)
|
||||
|
||||
# Placeholder GPS Information check
|
||||
if (self.GPS_msg.UTC_GPS_time != 0 or self.GPS_msg.UTC_GPS_time != 0):
|
||||
self.__gps_update()
|
||||
self.pub_GPS.publish(self.GPS_msg)
|
||||
|
||||
# rospy.loginfo(self.msg)
|
||||
r.sleep()
|
||||
|
||||
|
||||
|
||||
Reference in New Issue
Block a user