magni_info.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 
3 """
4 Copyright (c) 2020, Ubiquity Robotics
5 All rights reserved.
6 Redistribution and use in source and binary forms, with or without
7 modification, are permitted provided that the following conditions are met:
8 * Redistributions of source code must retain the above copyright notice, this
9  list of conditions and the following disclaimer.
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 * Neither the name of magni_robot nor the names of its
14  contributors may be used to endorse or promote products derived from
15  this software without specific prior written permission.
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
20 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
21 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
22 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
23 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
24 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
25 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 """
27 
28 """
29 magni_info is meant to gather up a variety of information for the Magni robot platform
30 A report is then generated with the latest system information available
31 """
32 
33 
34 
35 
36 import os
37 import sys
38 import subprocess
39 import psutil
40 import rospy
41 from sensor_msgs.msg import Range
42 class UbiquitySensors(object):
43  def __init__(self):
44  self.num_sonars = 5
45  self.sonar_ranges = [None] * self.num_sonars
46  rospy.Subscriber("/sonars", Range, self.rangeCallback)
47 
48  def rangeCallback(self, msg):
49  """Callback for sonars data."""
50  words = msg.header.frame_id.split('_')
51  idx = int(words[1])
52 
53  # save the most recent sonar range
54  self.sonar_ranges[idx] = msg.range
55 
56 
58  """Run topics and forward output to a file"""
59  if not os.path.exists('Topics.txt'):
60  os.system('touch Topics.txt')
61  if not os.path.exists('Nodes.txt'):
62  os.system('touch Nodes.txt')
63  if not os.path.exists('diagnostics.txt'):
64  os.system('touch diagnostics.txt')
65  os.system('rostopic list >> Topics.txt')
66  os.system('rosnode list >> Nodes.txt')
67  os.system('rostopic echo -n 10 /diagnostics > diagnostics.txt')
68 
69 
70 if __name__ == "__main__":
71 
72  rospy.init_node('magni_info')
75  periodicStatus = False
76  verboseOutput = False
77  loop_hz = 0.33
78  rate = rospy.Rate(loop_hz)
79 
80  # User input
81  argcount = len(sys.argv)
82  if argcount > 2:
83  print("Only -h for help or -p for periodic are allowed as arguments!")
84  sys.exit()
85 
86  # Possible options
87  if argcount == 2:
88  if sys.argv[1] == '-h' or sys.argv[1] == '--help':
89  print("Inspect key system parameters and exit by default")
90  print("use -p for remaining active and monitoring some system parameters")
91  sys.exit()
92  elif sys.argv[1] == '-v' or sys.argv[1] == '--verbose':
93  # set level of verbosity higher
94  verboseOutput = True
95  elif sys.argv[1] == '-p' or sys.argv[1] == '--periodic':
96  # set periodicStatus to True for remaining in status update mode
97  periodicStatus = True
98  else:
99  print("Unrecognized option! We only support -h or -p")
100  sys.exit()
101 
102  print("\nMagni Robot System Information:")
103  os.system('date')
104  print("\n------------------------- Linux OS: --------------------------------")
105  os.system('hostnamectl')
106  print("\n------------------------- Host Information: -----------------------")
107  os.system('cat /sys/firmware/devicetree/base/model')
108  print("")
109  os.system('hostname -I')
110  print("\n------------------------- ROS Environmental variables: -------------")
111  os.system('printenv | grep ROS')
112  print("\n------------------------- Firmware information: --------------------")
113  os.system('grep -A 1 "Firmware Version" diagnostics.txt | head -2')
114  os.system('grep -A 1 "Firmware Date" diagnostics.txt | head -2')
115  os.system('grep -A 1 "Battery Voltage" diagnostics.txt | head -2')
116  os.system('grep -A 1 "Motor Power" diagnostics.txt | head -2')
117  print("\n------------------------- Detected I2C devices: --------------------")
118  # Stop the motor node
119  os.system('sudo systemctl stop magni-base.service')
120  os.system('sudo i2cdetect -y 1')
121  # Restart magni-base service
122  os.system('sudo systemctl start magni-base.service')
123  print("\n------------------------- Key ROS Nodes: ---------------------------")
124  try:
125  out = subprocess.check_output(
126  ['grep', '-w', '/motor_node', 'Nodes.txt']).decode('utf-8')
127  sys.stdout.write(out)
128  except subprocess.CalledProcessError:
129  print("/motor_node not running!")
130  try:
131  out = subprocess.check_output(
132  ['grep', '-w', '/pi_sonar', 'Nodes.txt']).decode('utf-8')
133  sys.stdout.write(out)
134  except subprocess.CalledProcessError:
135  print("/pi_sonar not running!")
136  print("\n------------------------- Key ROS Topics: --------------------------")
137  try:
138  out = subprocess.check_output(
139  ['grep', '-w', '/cmd_vel', 'Topics.txt']).decode('utf-8')
140  sys.stdout.write(out)
141  except subprocess.CalledProcessError:
142  print("/cmd_vel topic not running!")
143  try:
144  out = subprocess.check_output(
145  ['grep', '-w', '/battery_state', 'Topics.txt']).decode('utf-8')
146  sys.stdout.write(out)
147  except subprocess.CalledProcessError:
148  print("/battery_state topic not running!")
149  print("\n------------------------ ROS Log Dir: -----------------------------")
150  os.system('roslaunch-logs')
151  print("\n------------------------ pifi Connectivity ------------------------")
152  os.system('pifi --version')
153  print("# Status: ")
154  os.system('pifi status')
155  print("# Seen Wifi's: ")
156  os.system('pifi list seen')
157  print("# Pending Wifi's: ")
158  os.system('pifi list pending')
159  print("\n------------------------ Key Device Info: -------------------------")
160  os.system('ls -d /dev/ttyAMA0 2>/dev/null')
161  os.system('ls -d /dev/ttyUSB* 2>/dev/null')
162  os.system('ls -d /dev/video0 2>/dev/null')
163  os.system('ls -d /dev/rtc0 2>/dev/null')
164  os.system('ls -d /dev/pigpio 2>/dev/null')
165  print("\n------------------------ Robot Config: ----------------------------")
166  os.system('cat /etc/ubiquity/robot.yaml')
167 
168  # Verbose option
169  if verboseOutput:
170  print("\n-------------------- Disk usage: ------------------------------")
171  os.system('df /')
172  print("\n-------------------- Memory Info: -----------------------------")
173  os.system('free | head -2')
174  print("\n-------------------- Processes: -------------------------------")
175  os.system('ps -ef')
176  print("\n-------------------- Device Info: -----------------------------")
177  os.system('ls -d /dev/*')
178  print("\n-------------------- Base Config: -----------------------------")
179  os.system('cat /opt/ros/kinetic/share/magni_bringup/param/base.yaml')
180  print("\n-------------------- Network ifconfig -------------------------")
181  os.system('ifconfig')
182  print("\n-------------------- Network iwconfig: ------------------------")
183  os.system('iwconfig')
184  print("\n-------------------- /etc/hosts file: -------------------------")
185  os.system('cat /etc/hosts')
186  print("\n-------------------- ROS Nodes: -------------------------------")
187  os.system('rosnode list')
188  print("\n-------------------- ROS Topics: ------------------------------")
189  os.system('rostopic list')
190  print("\n-------------------- .bashrc file -----------------------------")
191  os.system('cat ~/.bashrc')
192 
193  # Periodic option
194  if periodicStatus:
195  print("Periodic monitoring of the robot has been requested. Use Ctrl-C to exit!")
196 
197  # While our node is running
198  while not rospy.is_shutdown():
199  print(
200  "\n-------------------------------------------------------------------------------------")
201  print("------------------- Cpu and Memory Stats --------------------")
202  print('Cpu percent: % ', psutil.cpu_percent())
203  tot_m, used_m, free_m = map(int, os.popen(
204  'free -t -m').readlines()[-1].split()[1:])
205  print('Memory (in KBytes): Total %s Free %s Used %s ' %
206  (tot_m, free_m, used_m))
207  print("------------------- Sonar ranges: ---------------------------")
208  print(us.sonar_ranges)
209 
210  rate.sleep()
211 
212  # Delete temporary files
213  os.system('rm -f diagnostics.txt')
214  os.system('rm -f Nodes.txt')
215  os.system('rm -f Topics.txt')
216 
217  print('##### System information script done! #####')
def topics_to_file()
Definition: magni_info.py:57
def rangeCallback(self, msg)
Definition: magni_info.py:48


magni_bringup
Author(s):
autogenerated on Tue Jun 1 2021 02:33:35