4 Copyright (c) 2020, Ubiquity Robotics 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. 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 41 from sensor_msgs.msg
import Range
49 """Callback for sonars data.""" 50 words = msg.header.frame_id.split(
'_')
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')
70 if __name__ ==
"__main__":
72 rospy.init_node(
'magni_info')
75 periodicStatus =
False 78 rate = rospy.Rate(loop_hz)
81 argcount = len(sys.argv)
83 print(
"Only -h for help or -p for periodic are allowed as arguments!")
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")
92 elif sys.argv[1] ==
'-v' or sys.argv[1] ==
'--verbose':
95 elif sys.argv[1] ==
'-p' or sys.argv[1] ==
'--periodic':
99 print(
"Unrecognized option! We only support -h or -p")
102 print(
"\nMagni Robot System Information:")
104 print(
"\n------------------------- Linux OS: --------------------------------")
105 os.system(
'hostnamectl')
106 print(
"\n------------------------- Host Information: -----------------------")
107 os.system(
'cat /sys/firmware/devicetree/base/model')
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: --------------------")
119 os.system(
'sudo systemctl stop magni-base.service')
120 os.system(
'sudo i2cdetect -y 1')
122 os.system(
'sudo systemctl start magni-base.service')
123 print(
"\n------------------------- Key ROS Nodes: ---------------------------")
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!")
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: --------------------------")
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!")
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')
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')
170 print(
"\n-------------------- Disk usage: ------------------------------")
172 print(
"\n-------------------- Memory Info: -----------------------------")
173 os.system(
'free | head -2')
174 print(
"\n-------------------- Processes: -------------------------------")
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')
195 print(
"Periodic monitoring of the robot has been requested. Use Ctrl-C to exit!")
198 while not rospy.is_shutdown():
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)
213 os.system(
'rm -f diagnostics.txt')
214 os.system(
'rm -f Nodes.txt')
215 os.system(
'rm -f Topics.txt')
217 print(
'##### System information script done! #####')
def rangeCallback(self, msg)