Merge pull request #8 from captntuttle/System_Statuses

addes system status work to fixed branch
This commit is contained in:
Ken Steinfeldt
2018-01-30 09:46:56 -08:00
committed by GitHub
17 changed files with 958 additions and 0 deletions

View File

@@ -0,0 +1,211 @@
cmake_minimum_required(VERSION 2.8.3)
project(system_statuses)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
add_message_files(
FILES
RoverSysStatus.msg
BogieStatuses.msg
FrSkyStatus.msg
JetsonInfo.msg
CameraStatuses.msg
GPSInfo.msg
MiscStatuses.msg
)
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
generate_messages(
DEPENDENCIES
std_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES system_statuses
# CATKIN_DEPENDS roscpp rospy std_msgs
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/system_statuses.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/system_statuses_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_system_statuses.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

View File

@@ -0,0 +1,3 @@
int8 bogie_connection_1
int8 bogie_connection_2
int8 bogie_connection_3

View File

@@ -0,0 +1,4 @@
int8 camera_zed
int8 camera_undercarriage
int8 camera_chassis
int8 camera_main_navigation

View File

@@ -0,0 +1 @@
int8 FrSky_controller_connection_status

View File

@@ -0,0 +1,2 @@
int8 UTC_GPS_time
int8 GPS_connection_status

View File

@@ -0,0 +1,5 @@
float64 jetson_CPU
float64 jetson_RAM
float64 jetson_EMMC
float64 jetson_NVME_SSD
float64 jetson_GPU_temp

View 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

View File

@@ -0,0 +1,19 @@
int8 UTC_GPS_time
int8 bogie_connection_1
int8 bogie_connection_2
int8 bogie_connection_3
int8 arm_connection_status
int8 arm_end_effector_connection_statuses
int8 camera_zed
int8 camera_undercarriage
int8 camera_chassis
int8 camera_main_navigation
int8 sample_containment_connection_status
int8 tower_connection_status
int8 chassis_pan_tilt_connection_status
int8 GPS_connection_status
int8 jetson_CPU
int8 jetson_RAM
int8 jetson_EMMC
int8 jetson_NVME_SSD
int8 FrSky_controller_connection_status

View File

@@ -0,0 +1,68 @@
<?xml version="1.0"?>
<package format="2">
<name>system_statuses</name>
<version>0.0.0</version>
<description>The system_statuses package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="matcurtay@matcurtay.net">matcurtay</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>BSD</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/system_statuses</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<build_depend>message_generation</build_depend>
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<exec_depend>message_runtime</exec_depend>
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>

View File

@@ -0,0 +1,4 @@
<?xml version="1.0" encoding="UTF-8"?>
<project version="4">
<component name="ProjectRootManager" version="2" project-jdk-name="Python 2.7" project-jdk-type="Python SDK" />
</project>

View File

@@ -0,0 +1,8 @@
<?xml version="1.0" encoding="UTF-8"?>
<project version="4">
<component name="ProjectModuleManager">
<modules>
<module fileurl="file://$PROJECT_DIR$/.idea/scripts.iml" filepath="$PROJECT_DIR$/.idea/scripts.iml" />
</modules>
</component>
</project>

View File

@@ -0,0 +1,12 @@
<?xml version="1.0" encoding="UTF-8"?>
<module type="PYTHON_MODULE" version="4">
<component name="NewModuleRootManager">
<content url="file://$MODULE_DIR$" />
<orderEntry type="inheritedJdk" />
<orderEntry type="sourceFolder" forTests="false" />
</component>
<component name="TestRunnerService">
<option name="projectConfiguration" value="Nosetests" />
<option name="PROJECT_TEST_RUNNER" value="Nosetests" />
</component>
</module>

View File

@@ -0,0 +1,266 @@
<?xml version="1.0" encoding="UTF-8"?>
<project version="4">
<component name="ChangeListManager">
<list default="true" id="70471578-1307-4c98-9010-bffc2d7cc71c" name="Default" comment="" />
<option name="EXCLUDED_CONVERTED_TO_IGNORED" value="true" />
<option name="TRACKING_ENABLED" value="true" />
<option name="SHOW_DIALOG" value="false" />
<option name="HIGHLIGHT_CONFLICTS" value="true" />
<option name="HIGHLIGHT_NON_ACTIVE_CHANGELIST" value="false" />
<option name="LAST_RESOLUTION" value="IGNORE" />
</component>
<component name="FileEditorManager">
<leaf SIDE_TABS_SIZE_LIMIT_KEY="525">
<file leaf-file-name="system_statuses_node.py" pinned="false" current-in-tab="true">
<entry file="file://$PROJECT_DIR$/system_statuses_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="401">
<caret line="121" column="65" lean-forward="false" selection-start-line="121" selection-start-column="65" selection-end-line="121" selection-end-column="65" />
<folding>
<element signature="e#22#34#0" expanded="true" />
<element signature="e#6507#6798#0" expanded="false" />
<element signature="e#7227#7327#0" expanded="false" />
<element signature="e#7380#7602#0" expanded="false" />
<element signature="e#7653#7788#0" expanded="false" />
<element signature="e#7840#8331#0" expanded="false" />
<marker date="1517104529510" expanded="true" signature="6455:8331" ph="..." />
</folding>
</state>
</provider>
</entry>
</file>
<file leaf-file-name="rover_statuses.py" pinned="false" current-in-tab="false">
<entry file="file://$PROJECT_DIR$/rover_statuses.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="226">
<caret line="53" column="62" lean-forward="false" selection-start-line="53" selection-start-column="62" selection-end-line="53" selection-end-column="62" />
<folding>
<element signature="e#22#34#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
</file>
</leaf>
</component>
<component name="FileTemplateManagerImpl">
<option name="RECENT_TEMPLATES">
<list>
<option value="Python Script" />
</list>
</option>
</component>
<component name="IdeDocumentHistory">
<option name="CHANGED_PATHS">
<list>
<option value="$PROJECT_DIR$/system_statuses.py" />
<option value="$PROJECT_DIR$/node_statuses.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>
<component name="JsBuildToolGruntFileManager" detection-done="true" sorting="DEFINITION_ORDER" />
<component name="JsBuildToolPackageJson" detection-done="true" sorting="DEFINITION_ORDER" />
<component name="JsGulpfileManager">
<detection-done>true</detection-done>
<sorting>DEFINITION_ORDER</sorting>
</component>
<component name="ProjectFrameBounds">
<option name="x" value="1063" />
<option name="y" value="534" />
<option name="width" value="1650" />
<option name="height" value="1043" />
</component>
<component name="ProjectView">
<navigator currentView="ProjectPane" proportions="" version="1">
<flattenPackages />
<showMembers />
<showModules />
<showLibraryContents />
<hideEmptyPackages />
<abbreviatePackageNames />
<autoscrollToSource />
<autoscrollFromSource />
<sortByType />
<manualOrder />
<foldersAlwaysOnTop value="true" />
</navigator>
<panes>
<pane id="Scratches" />
<pane id="ProjectPane">
<subPane>
<expand>
<path>
<item name="scripts" type="b2602c69:ProjectViewProjectNode" />
<item name="scripts" type="462c0819:PsiDirectoryNode" />
</path>
</expand>
<select />
</subPane>
</pane>
<pane id="Scope" />
</panes>
</component>
<component name="PropertiesComponent">
<property name="nodejs_interpreter_path.stuck_in_default_project" value="undefined stuck path" />
<property name="WebServerToolWindowFactoryState" value="false" />
<property name="last_opened_file_path" value="$PROJECT_DIR$" />
</component>
<component name="RunDashboard">
<option name="ruleStates">
<list>
<RuleState>
<option name="name" value="ConfigurationTypeDashboardGroupingRule" />
</RuleState>
<RuleState>
<option name="name" value="StatusDashboardGroupingRule" />
</RuleState>
</list>
</option>
</component>
<component name="ShelveChangesManager" show_recycled="false">
<option name="remove_strategy" value="false" />
</component>
<component name="SvnConfiguration">
<configuration />
</component>
<component name="TaskManager">
<task active="true" id="Default" summary="Default task">
<changelist id="70471578-1307-4c98-9010-bffc2d7cc71c" name="Default" comment="" />
<created>1515892189770</created>
<option name="number" value="Default" />
<option name="presentableId" value="Default" />
<updated>1515892189770</updated>
</task>
<servers />
</component>
<component name="ToolWindowManager">
<frame x="1063" y="534" width="1650" height="1043" extended-state="0" />
<editor active="true" />
<layout>
<window_info id="TODO" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="6" side_tool="false" content_ui="tabs" />
<window_info id="Event Log" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="7" side_tool="true" content_ui="tabs" />
<window_info id="Version Control" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="false" weight="0.33" sideWeight="0.5" order="11" side_tool="false" content_ui="tabs" />
<window_info id="Python Console" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="8" side_tool="false" content_ui="tabs" />
<window_info id="Run" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="2" side_tool="false" content_ui="tabs" />
<window_info id="Terminal" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="9" side_tool="false" content_ui="tabs" />
<window_info id="Project" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="true" show_stripe_button="true" weight="0.11233211" sideWeight="0.5" order="0" side_tool="false" content_ui="combo" />
<window_info id="Docker" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="false" weight="0.33" sideWeight="0.5" order="10" side_tool="false" content_ui="tabs" />
<window_info id="Database" active="false" anchor="right" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="3" side_tool="false" content_ui="tabs" />
<window_info id="SciView" active="false" anchor="right" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="4" side_tool="false" content_ui="tabs" />
<window_info id="Structure" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.25" sideWeight="0.5" order="1" side_tool="false" content_ui="tabs" />
<window_info id="Favorites" active="false" anchor="left" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="2" side_tool="true" content_ui="tabs" />
<window_info id="Debug" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.4" sideWeight="0.5" order="3" side_tool="false" content_ui="tabs" />
<window_info id="Cvs" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.25" sideWeight="0.5" order="4" side_tool="false" content_ui="tabs" />
<window_info id="Message" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.33" sideWeight="0.5" order="0" side_tool="false" content_ui="tabs" />
<window_info id="Commander" active="false" anchor="right" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.4" sideWeight="0.5" order="0" side_tool="false" content_ui="tabs" />
<window_info id="Inspection" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.4" sideWeight="0.5" order="5" side_tool="false" content_ui="tabs" />
<window_info id="Hierarchy" active="false" anchor="right" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.25" sideWeight="0.5" order="2" side_tool="false" content_ui="combo" />
<window_info id="Find" active="false" anchor="bottom" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.3294347" sideWeight="0.5" order="1" side_tool="false" content_ui="tabs" />
<window_info id="Ant Build" active="false" anchor="right" auto_hide="false" internal_type="DOCKED" type="DOCKED" visible="false" show_stripe_button="true" weight="0.25" sideWeight="0.5" order="1" side_tool="false" content_ui="tabs" />
</layout>
</component>
<component name="TypeScriptGeneratedFilesManager">
<option name="version" value="1" />
</component>
<component name="VcsContentAnnotationSettings">
<option name="myLimit" value="2678400000" />
</component>
<component name="XDebuggerManager">
<breakpoint-manager>
<option name="time" value="5" />
</breakpoint-manager>
<watches-manager />
</component>
<component name="editorHistoryManager">
<entry file="file://$PROJECT_DIR$/system_statuses_node.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="2976">
<caret line="124" column="61" lean-forward="false" selection-start-line="124" selection-start-column="61" selection-end-line="124" selection-end-column="61" />
<folding>
<element signature="e#22#34#0" expanded="true" />
<element signature="e#6507#6798#0" expanded="false" />
<element signature="e#7227#7327#0" expanded="false" />
<element signature="e#7380#7602#0" expanded="false" />
<element signature="e#7653#7788#0" expanded="false" />
<element signature="e#7840#8331#0" expanded="false" />
<marker date="1517104529510" expanded="true" signature="6455:8331" ph="..." />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/rover_statuses.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="1248">
<caret line="53" column="37" lean-forward="false" selection-start-line="53" selection-start-column="37" selection-end-line="53" selection-end-column="37" />
<folding>
<element signature="e#22#34#0" expanded="true" />
</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="0">
<caret line="0" column="0" lean-forward="false" selection-start-line="0" selection-start-column="0" selection-end-line="0" selection-end-column="0" />
<folding>
<element signature="e#22#34#0" expanded="true" />
<element signature="e#6507#6798#0" expanded="false" />
<element signature="e#7227#7327#0" expanded="false" />
<element signature="e#7380#7602#0" expanded="false" />
<element signature="e#7653#7788#0" expanded="false" />
<element signature="e#7840#8331#0" expanded="false" />
<marker date="1517104529510" expanded="true" signature="6455:8331" ph="..." />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/rover_statuses.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="648">
<caret line="28" column="17" lean-forward="false" selection-start-line="28" selection-start-column="17" selection-end-line="28" selection-end-column="17" />
<folding>
<element signature="e#22#34#0" expanded="true" />
</folding>
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/system_statuses.py" />
<entry file="file://$PROJECT_DIR$/node_statuses.py" />
<entry file="file://$PROJECT_DIR$/camera_2_updater.py">
<provider selected="true" editor-type-id="text-editor">
<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" />
</state>
</provider>
</entry>
<entry file="file://$PROJECT_DIR$/rover_statuses.py">
<provider selected="true" editor-type-id="text-editor">
<state relative-caret-position="226">
<caret line="53" column="62" lean-forward="false" selection-start-line="53" selection-start-column="62" selection-end-line="53" selection-end-column="62" />
<folding>
<element signature="e#22#34#0" expanded="true" />
</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="401">
<caret line="121" column="65" lean-forward="false" selection-start-line="121" selection-start-column="65" selection-end-line="121" selection-end-column="65" />
<folding>
<element signature="e#22#34#0" expanded="true" />
<element signature="e#6507#6798#0" expanded="false" />
<element signature="e#7227#7327#0" expanded="false" />
<element signature="e#7380#7602#0" expanded="false" />
<element signature="e#7653#7788#0" expanded="false" />
<element signature="e#7840#8331#0" expanded="false" />
<marker date="1517104529510" expanded="true" signature="6455:8331" ph="..." />
</folding>
</state>
</provider>
</entry>
</component>
</project>

View File

@@ -0,0 +1,26 @@
#!/usr/bin/env python
# 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
# 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.)
#if __name__ == '__main__':
# try:
# camera_2_changer()
# except rospy.ROSInterruptException:
# pass

View File

@@ -0,0 +1,80 @@
#!/usr/bin/env python
import rospy
from system_statuses.msg import CameraStatuses, BogieStatuses, FrSkyStatus, GPSInfo, MiscStatuses, JetsonInfo
# THIS IS A SUPER ROUGH EXAMPLE OF HOW TO PULL THE DATA
# You can create your own message formats in the msg folder
# This is a simple example of pulling data from system_statuses_node.py
# and storing them into self values.
# The ground control code sounds like it'll be fairly different in format.
class RoverStatuses:
def __init__(self):
rospy.init_node('RoverStatuses')
# self.pub = rospy.Publisher('rover_statuses_chatter', RoverSysStatus, queue_size=10)
# Subscription examples on pulling data from system_statuses_node.py
rospy.Subscriber('camera_system_status_chatter', CameraStatuses, self.__camera_callback)
rospy.Subscriber('bogie_system_status_chatter', BogieStatuses, self.__bogie_callback)
rospy.Subscriber('FrSky_system_status_chatter', FrSkyStatus, self.__frsky_callback)
rospy.Subscriber('GPS_system_status_chatter', GPSInfo, self.__gps_callback)
rospy.Subscriber('jetson_system_status_chatter', JetsonInfo, self.__jetson_callback)
rospy.Subscriber('misc_system_status_chatter', MiscStatuses, self.__misc_callback)
self.camera_msg = CameraStatuses()
self.bogie_msg = BogieStatuses()
self.FrSky_msg = FrSkyStatus()
self.GPS_msg = GPSInfo()
self.jetson_msg = JetsonInfo()
self.misc_msg = MiscStatuses()
def __camera_callback(self, data):
self.camera_msg.camera_zed = data.camera_zed
self.camera_msg.camera_undercarriage = data.camera_undercarriage
self.camera_msg.camera_chassis = data.camera_chassis
self.camera_msg.camera_main_navigation = data.camera_main_navigation
def __frsky_callback(self, data):
self.FrSky_msg.FrSky_controller_connection_status = data.FrSky_controller_connection_status
def __bogie_callback(self, data):
self.bogie_msg.bogie_connection_1 = data.bogie_connection_1
self.bogie_msg.bogie_connection_2 = data.bogie_connection_2
self.bogie_msg.bogie_connection_3 = data.bogie_connection_3
def __jetson_callback(self, data):
self.jetson_msg.jetson_CPU = data.jetson_CPU
self.jetson_msg.jetson_RAM = data.jetson_RAM
self.jetson_msg.jetson_EMMC = data.jetson_EMMC
self.jetson_msg.jetson_NVME_SSD = data.jetson_NVME_SSD
self.jetson_msg.jetson_GPU_temp = data.jetson_GPU_temp
rospy.loginfo(self.jetson_msg)
def __gps_callback(self, data):
self.GPS_msg.UTC_GPS_time = data.UTC_GPS_time
self.GPS_msg.GPS_connection_status = data.GPS_connection_status
def __misc_callback(self, data):
self.misc_msg.arm_connection_status = data.arm_connection_status
self.misc_msg.arm_end_effector_connection_statuses = data.arm_end_effector_connection_statuses
self.misc_msg.sample_containment_connection_status = data.sample_containment_connection_status
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 run(self):
rospy.Subscriber('camera_system_status_chatter', CameraStatuses, self.__camera_callback)
rospy.Subscriber('bogie_system_status_chatter', BogieStatuses, self.__bogie_callback)
rospy.Subscriber('FrSky_system_status_chatter', FrSkyStatus, self.__frsky_callback)
rospy.Subscriber('GPS_system_status_chatter', GPSInfo, self.__gps_callback)
rospy.Subscriber('jetson_system_status_chatter', JetsonInfo, self.__jetson_callback)
rospy.Subscriber('misc_system_status_chatter', MiscStatuses, self.__misc_callback)
rospy.spin()
if __name__ == '__main__':
rover_statuses = RoverStatuses()
rover_statuses.run()

View File

@@ -0,0 +1,244 @@
#!/usr/bin/env python
import rospy
import os.path
import psutil
import subprocess
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',
'/dev/rover/camera_chassis',
'/dev/rover/camera_main_navigation'
]
# filesystem paths for EMMC [0] and NVME_SSD [1]
# -- UPDATE [1] FOR JETSON --
self.file_systems_EMMC_NVMe_SSD = [
'/',
'/dev/shm'
]
rospy.init_node('SystemStatuses')
# 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)
# 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()
# init all message values
self.__pull_new_message_values()
# init all previous values
self.__update_all_previous_values()
# init all RoverSysMessage values
def __pull_new_message_values(self):
self.__set_gps_info()
self.__set_bogie_connection_statuses()
self.__set_arm_connection_status()
self.__set_arm_end_effector_connection_statuses()
self.__set_cameras()
self.__set_sample_containment_connection_status()
self.__set_tower_connection_status()
self.__set_chassis_pan_tilt_connection_status()
self.__set_jetson_usage_information()
self.__set_frsky_controller_connection_status()
# Pulls the UTC GPS Time (WIP)
def __set_gps_info(self):
self.GPS_msg.UTC_GPS_time = 0
self.GPS_msg.GPS_connection_status = 0
# Pulls bogie connection statuses (WIP)
def __set_bogie_connection_statuses(self):
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 __set_arm_connection_status(self):
self.misc_msg.arm_connection_status = 0
# Checks Arm End Effector Connection Statuses (WIP)
def __set_arm_end_effector_connection_statuses(self):
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.camera_msg.camera_zed = 1 if os.path.exists(self.system_path_locations[0]) else 0
# Check if camera_undercarriage is found
self.camera_msg.camera_undercarriage = 1 if os.path.exists(self.system_path_locations[1]) else 0
# Check if camera_chassis is found
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.camera_msg.camera_main_navigation = 1 if os.path.exists(self.system_path_locations[3]) else 0
# Checks Sample Containment Connection Status (WIP)
def __set_sample_containment_connection_status(self):
self.misc_msg.sample_containment_connection_status = 0
def __set_tower_connection_status(self):
self.misc_msg.tower_connection_status = 0
# Checks Tower Connection Status (WIP)
def __set_chassis_pan_tilt_connection_status(self):
self.misc_msg.chassis_pan_tilt_connection_status = 0
# Get Jetson Statuses (WIP)
def __set_jetson_usage_information(self):
self.jetson_msg.jetson_CPU = psutil.cpu_percent()
mem = psutil.virtual_memory()
self.jetson_msg.jetson_RAM = mem.percent
self.jetson_msg.jetson_EMMC = self.__used_percent_fs(self.file_systems_EMMC_NVMe_SSD[0])
self.jetson_msg.jetson_NVME_SSD = self.__used_percent_fs(self.file_systems_EMMC_NVMe_SSD[1])
# Temperature
# This try except causes a bunch of annoying messages, but lets it run on non-jetson devices
# sets to -1.0 if sensor fails to give it a default value notifying failure to pull
try:
sensor_temperatures = subprocess.check_output("sensors | grep temp", shell=True)
parsed_temps = sensor_temperatures.replace("\xc2\xb0C","").replace("(crit = ","").replace("temp1:","")\
.replace("\n","").replace("+","").split()
self.jetson_msg.jetson_GPU_temp = parsed_temps[4]
except subprocess.CalledProcessError:
print 'sensors call failed (potential reason: on VM)'
self.jetson_msg.jetson_GPU_temp = -1.0
# EMMC and NVMe_SSD used % calculation
def __used_percent_fs(self, pathname):
statvfs = os.statvfs(pathname)
# percentage :: USED:
# used amount: blocks - bfree
# used%: used_amount / (used_amount + bavail)
used_available = (statvfs.f_frsize * statvfs.f_blocks / 1024) - (statvfs.f_frsize * statvfs.f_bfree / 1024.0)
used_percent = used_available / (used_available + (statvfs.f_frsize * statvfs.f_bavail / 1024.0))
# Round 4 for 2 decimal accuracy
value = 100 * round(used_percent, 4)
return value
# Check FrSky Controller Connection Status (WIP)
def __set_frsky_controller_connection_status(self):
self.FrSky_msg.FrSky_controller_connection_status = 0
# Used mainly for init, sets all previous values in one go
def __update_all_previous_values(self):
self.__set_previous_camera_values()
self.__set_previous_jetson_values()
self.__set_previous_frsky_value()
self.__set_previous_bogie_values()
self.__set_previous_gps_values()
self.__set_previous_misc_values()
def __set_previous_camera_values(self):
self.previous_camera_zed = self.camera_msg.camera_zed
self.previous_camera_undercarriage = self.camera_msg.camera_undercarriage
self.previous_camera_chassis = self.camera_msg.camera_chassis
self.previous_camera_main_navigation = self.camera_msg.camera_main_navigation
def __set_previous_jetson_values(self):
self.previous_jetson_CPU = self.jetson_msg.jetson_CPU
self.previous_jetson_RAM = self.jetson_msg.jetson_RAM
self.previous_jetson_EMMC = self.jetson_msg.jetson_EMMC
self.previous_jetson_NVME_SSD = self.jetson_msg.jetson_NVME_SSD
self.previous_jetson_GPU_temp = self.jetson_msg.jetson_GPU_temp
def __set_previous_frsky_value(self):
self.previous_FrSky_controller_connection_status = self.FrSky_msg.FrSky_controller_connection_status
def __set_previous_bogie_values(self):
self.previous_bogie_connection_1 = self.bogie_msg.bogie_connection_1
self.previous_bogie_connection_2 = self.bogie_msg.bogie_connection_2
self.previous_bogie_connection_3 = self.bogie_msg.bogie_connection_3
def __set_previous_gps_values(self):
self.previous_UTC_GPS_time = self.GPS_msg.UTC_GPS_time
self.previous_GPS_connection_status = self.GPS_msg.GPS_connection_status
def __set_previous_misc_values(self):
self.previous_arm_connection_status = self.misc_msg.arm_connection_status
self.previous_arm_end_effector_connection_statuses = self.misc_msg.arm_end_effector_connection_statuses
self.previous_chassis_pan_tilt_connection_status = self.misc_msg.chassis_pan_tilt_connection_status
self.previous_sample_containment_connection_status = self.misc_msg.sample_containment_connection_status
self.previous_tower_connection_status = self.misc_msg.tower_connection_status
def run(self):
r = rospy.Rate(10) # 10Hz
while not rospy.is_shutdown():
# Update all message values
self.__pull_new_message_values()
# Camera Check -- if current value is now different from previous value,
# update the previous value for cameras and publish to listening Subscribers
if (self.camera_msg.camera_zed != self.previous_camera_zed or
self.camera_msg.camera_undercarriage != self.previous_camera_undercarriage or
self.camera_msg.camera_chassis != self.previous_camera_chassis or
self.camera_msg.camera_main_navigation != self.previous_camera_main_navigation):
self.__set_previous_camera_values()
self.pub_camera.publish(self.camera_msg)
# Placeholder Jetson Info Check
if (self.jetson_msg.jetson_CPU != self.previous_jetson_CPU or
self.jetson_msg.jetson_RAM != self.previous_jetson_RAM or
self.jetson_msg.jetson_EMMC != self.previous_jetson_EMMC or
self.jetson_msg.jetson_NVME_SSD != self.previous_jetson_NVME_SSD or
self.jetson_msg.jetson_GPU_temp != self.previous_jetson_GPU_temp):
self.__set_previous_jetson_values()
self.pub_jetson.publish(self.jetson_msg)
# Placeholder FrSky Controller Check
if self.FrSky_msg.FrSky_controller_connection_status != self.previous_FrSky_controller_connection_status:
self.__set_previous_frsky_value()
self.pub_FrSky.publish(self.FrSky_msg)
# Placeholder bogie status check
if (self.bogie_msg.bogie_connection_1 != self.previous_bogie_connection_1 or
self.bogie_msg.bogie_connection_2 != self.previous_bogie_connection_2 or
self.bogie_msg.bogie_connection_3 != self.previous_bogie_connection_3):
self.__set_previous_bogie_values()
self.pub_bogie.publish(self.bogie_msg)
# Placeholder GPS Information check
if (self.GPS_msg.UTC_GPS_time != self.previous_UTC_GPS_time or
self.GPS_msg.UTC_GPS_time != self.previous_GPS_connection_status):
self.__set_previous_gps_values()
self.pub_GPS.publish(self.GPS_msg)
# Placeholder Misc Information check
if (self.misc_msg.arm_connection_status !=
self.previous_arm_connection_status or
self.misc_msg.arm_end_effector_connection_statuses !=
self.previous_arm_end_effector_connection_statuses or
self.misc_msg.chassis_pan_tilt_connection_status !=
self.previous_chassis_pan_tilt_connection_status or
self.misc_msg.sample_containment_connection_status !=
self.previous_sample_containment_connection_status or
self.misc_msg.tower_connection_status !=
self.previous_tower_connection_status):
self.__set_previous_misc_values()
self.pub_Misc.publish(self.misc_msg)
# rospy.loginfo(self.msg)
r.sleep()
if __name__ == '__main__':
system_status = SystemStatuses()
system_status.run()