selfcheck.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # coding=utf-8
3 
4 # Copyright (C) 2018 Copter Express Technologies
5 #
6 # Author: Oleg Kalachev <okalachev@gmail.com>
7 #
8 # Distributed under MIT License (available at https://opensource.org/licenses/MIT).
9 # The above copyright notice and this permission notice shall be included in all
10 # copies or substantial portions of the Software.
11 
12 import os
13 import math
14 import subprocess
15 import re
16 from collections import OrderedDict
17 import traceback
18 from threading import Event
19 import numpy
20 import rospy
21 import tf2_ros
22 import tf2_geometry_msgs
23 from pymavlink import mavutil
24 from std_srvs.srv import Trigger
25 from sensor_msgs.msg import BatteryState, Image, CameraInfo, NavSatFix, Imu, Range
26 from mavros_msgs.msg import State, OpticalFlowRad, Mavlink
27 from mavros_msgs.srv import ParamGet
28 from geometry_msgs.msg import PoseStamped, TwistStamped, PoseWithCovarianceStamped, Vector3Stamped
29 from visualization_msgs.msg import MarkerArray as VisualizationMarkerArray
30 import tf.transformations as t
31 from aruco_pose.msg import MarkerArray
32 from mavros import mavlink
33 
34 
35 # TODO: check attitude is present
36 # TODO: disk free space
37 # TODO: map, base_link, body
38 # TODO: rc service
39 # TODO: perform commander check, ekf2 status on PX4
40 # TODO: check if FCU params setter succeed
41 # TODO: selfcheck ROS service (with blacklists for checks)
42 
43 
44 rospy.init_node('selfcheck')
45 
46 
47 tf_buffer = tf2_ros.Buffer()
48 tf_listener = tf2_ros.TransformListener(tf_buffer)
49 
50 
51 failures = []
52 infos = []
53 current_check = None
54 
55 
56 def failure(text, *args):
57  msg = text % args
58  rospy.logwarn('%s: %s', current_check, msg)
59  failures.append(msg)
60 
61 
62 def info(text, *args):
63  msg = text % args
64  rospy.loginfo('%s: %s', current_check, msg)
65  infos.append(msg)
66 
67 
68 def check(name):
69  def inner(fn):
70  def wrapper(*args, **kwargs):
71  failures[:] = []
72  infos[:] = []
73  global current_check
74  current_check = name
75  try:
76  fn(*args, **kwargs)
77  except Exception as e:
78  traceback.print_exc()
79  rospy.logerr('%s: exception occurred', name)
80  return
81  if not failures and not infos:
82  rospy.loginfo('%s: OK', name)
83  return wrapper
84  return inner
85 
86 
87 param_get = rospy.ServiceProxy('mavros/param/get', ParamGet)
88 
89 
90 def get_param(name):
91  try:
92  res = param_get(param_id=name)
93  except rospy.ServiceException as e:
94  failure('%s: %s', name, str(e))
95  return None
96 
97  if not res.success:
98  failure('unable to retrieve PX4 parameter %s', name)
99  else:
100  if res.value.integer != 0:
101  return res.value.integer
102  return res.value.real
103 
104 
105 recv_event = Event()
106 link = mavutil.mavlink.MAVLink('', 255, 1)
107 mavlink_pub = rospy.Publisher('mavlink/to', Mavlink, queue_size=1)
108 mavlink_recv = ''
109 
110 
112  global mavlink_recv
113  if msg.msgid == 126:
114  mav_bytes_msg = mavlink.convert_to_bytes(msg)
115  mav_msg = link.decode(mav_bytes_msg)
116  mavlink_recv += ''.join(chr(x) for x in mav_msg.data[:mav_msg.count])
117  if 'nsh>' in mavlink_recv:
118  # Remove the last line, including newline before prompt
119  mavlink_recv = mavlink_recv[:mavlink_recv.find('nsh>') - 1]
120  recv_event.set()
121 
122 
123 mavlink_sub = rospy.Subscriber('mavlink/from', Mavlink, mavlink_message_handler)
124 # FIXME: not sleeping here still breaks things
125 rospy.sleep(0.5)
126 
127 
128 def mavlink_exec(cmd, timeout=3.0):
129  global mavlink_recv
130  mavlink_recv = ''
131  recv_event.clear()
132  if not cmd.endswith('\n'):
133  cmd += '\n'
134  msg = mavutil.mavlink.MAVLink_serial_control_message(
135  device=mavutil.mavlink.SERIAL_CONTROL_DEV_SHELL,
136  flags=mavutil.mavlink.SERIAL_CONTROL_FLAG_RESPOND | mavutil.mavlink.SERIAL_CONTROL_FLAG_EXCLUSIVE |
137  mavutil.mavlink.SERIAL_CONTROL_FLAG_MULTI,
138  timeout=3,
139  baudrate=0,
140  count=len(cmd),
141  data=map(ord, cmd.ljust(70, '\0')))
142  msg.pack(link)
143  ros_msg = mavlink.convert_to_rosmsg(msg)
144  mavlink_pub.publish(ros_msg)
145  recv_event.wait(timeout)
146  return mavlink_recv
147 
148 
149 BOARD_ROTATIONS = {
150  0: 'no rotation',
151  1: 'yaw 45°',
152  2: 'yaw 90°',
153  3: 'yaw 135°',
154  4: 'yaw 180°',
155  5: 'yaw 225°',
156  6: 'yaw 270°',
157  7: 'yaw 315°',
158  8: 'roll 180°',
159  9: 'roll 180°, yaw 45°',
160  10: 'roll 180°, yaw 90°',
161  11: 'roll 180°, yaw 135°',
162  12: 'pitch 180°',
163  13: 'roll 180°, yaw 225°',
164  14: 'roll 180°, yaw 270°',
165  15: 'roll 180°, yaw 315°',
166  16: 'roll 90°',
167  17: 'roll 90°, yaw 45°',
168  18: 'roll 90°, yaw 90°',
169  19: 'roll 90°, yaw 135°',
170  20: 'roll 270°',
171  21: 'roll 270°, yaw 45°',
172  22: 'roll 270°, yaw 90°',
173  23: 'roll 270°, yaw 135°',
174  24: 'pitch 90°',
175  25: 'pitch 270°',
176  26: 'roll 270°, yaw 270°',
177  27: 'roll 180°, pitch 270°',
178  28: 'pitch 90°, yaw 180',
179  29: 'pitch 90°, roll 90°',
180  30: 'yaw 293°, pitch 68°, roll 90°',
181  31: 'pitch 90°, roll 270°',
182  32: 'pitch 9°, yaw 180°',
183  33: 'pitch 45°',
184  34: 'pitch 315°',
185 }
186 
187 
188 @check('FCU')
189 def check_fcu():
190  try:
191  state = rospy.wait_for_message('mavros/state', State, timeout=3)
192  if not state.connected:
193  failure('no connection to the FCU (check wiring)')
194  return
195 
196  # Make sure the console is available to us
197  mavlink_exec('\n')
198  version_str = mavlink_exec('ver all')
199  if version_str == '':
200  info('no version data available from SITL')
201 
202  r = re.compile(r'^FW (git tag|version): (v?\d\.\d\.\d.*)$')
203  is_clover_firmware = False
204  for ver_line in version_str.split('\n'):
205  match = r.search(ver_line)
206  if match is not None:
207  field, version = match.groups()
208  info('firmware %s: %s' % (field, version))
209  if 'clover' in version or 'clever' in version:
210  is_clover_firmware = True
211 
212  if not is_clover_firmware:
213  failure('not running Clover PX4 firmware, https://clover.coex.tech/firmware')
214 
215  est = get_param('SYS_MC_EST_GROUP')
216  if est == 1:
217  info('selected estimator: LPE')
218  fuse = get_param('LPE_FUSION')
219  if fuse & (1 << 4):
220  info('LPE_FUSION: land detector fusion is enabled')
221  else:
222  info('LPE_FUSION: land detector fusion is disabled')
223  if fuse & (1 << 7):
224  info('LPE_FUSION: barometer fusion is enabled')
225  else:
226  info('LPE_FUSION: barometer fusion is disabled')
227 
228  mag_yaw_w = get_param('ATT_W_MAG')
229  if mag_yaw_w == 0:
230  info('magnetometer weight (ATT_W_MAG) is zero, better for indoor flights')
231  else:
232  info('magnetometer weight (ATT_W_MAG) is non-zero (%.2f), better for outdoor flights', mag_yaw_w)
233 
234  elif est == 2:
235  info('selected estimator: EKF2')
236  else:
237  failure('unknown selected estimator: %s', est)
238 
239  rot = get_param('SENS_BOARD_ROT')
240  if rot is not None:
241  try:
242  info('board rotation: %s', BOARD_ROTATIONS[rot])
243  except KeyError:
244  failure('unknown board rotation %s', rot)
245 
246  cbrk_usb_chk = get_param('CBRK_USB_CHK')
247  if cbrk_usb_chk != 197848:
248  failure('set parameter CBRK_USB_CHK to 197848 for flying with USB connected')
249 
250  try:
251  battery = rospy.wait_for_message('mavros/battery', BatteryState, timeout=3)
252  if not battery.cell_voltage:
253  failure('cell voltage is not available, https://clover.coex.tech/power')
254  else:
255  cell = battery.cell_voltage[0]
256  if cell > 4.3 or cell < 3.0:
257  failure('incorrect cell voltage: %.2f V, https://clover.coex.tech/power', cell)
258  elif cell < 3.7:
259  failure('critically low cell voltage: %.2f V, recharge battery', cell)
260  except rospy.ROSException:
261  failure('no battery state')
262 
263  except rospy.ROSException:
264  failure('no MAVROS state (check wiring)')
265 
266 
268  if v.x > 0.9:
269  return 'forward'
270  elif v.x < - 0.9:
271  return 'backward'
272  elif v.y > 0.9:
273  return 'left'
274  elif v.y < -0.9:
275  return 'right'
276  elif v.z > 0.9:
277  return 'upward'
278  elif v.z < -0.9:
279  return 'downward'
280  else:
281  return None
282 
283 
284 def check_camera(name):
285  try:
286  img = rospy.wait_for_message(name + '/image_raw', Image, timeout=1)
287  except rospy.ROSException:
288  failure('%s: no images (is the camera connected properly?)', name)
289  return
290  try:
291  camera_info = rospy.wait_for_message(name + '/camera_info', CameraInfo, timeout=1)
292  except rospy.ROSException:
293  failure('%s: no calibration info', name)
294  return
295 
296  if img.width != camera_info.width:
297  failure('%s: calibration width doesn\'t match image width (%d != %d)', name, camera_info.width, img.width)
298  if img.height != camera_info.height:
299  failure('%s: calibration height doesn\'t match image height (%d != %d))', name, camera_info.height, img.height)
300 
301  try:
302  optical = Vector3Stamped()
303  optical.header.frame_id = img.header.frame_id
304  optical.vector.z = 1
305  cable = Vector3Stamped()
306  cable.header.frame_id = img.header.frame_id
307  cable.vector.y = 1
308 
309  optical = describe_direction(tf_buffer.transform(optical, 'base_link').vector)
310  cable = describe_direction(tf_buffer.transform(cable, 'base_link').vector)
311  if not optical or not cable:
312  info('%s: custom camera orientation detected', name)
313  else:
314  info('camera is oriented %s, cable from camera goes %s', optical, cable)
315 
316  except tf2_ros.TransformException:
317  failure('cannot transform from base_link to camera frame')
318 
319 
320 @check('Main camera')
322  check_camera('main_camera')
323 
324 
325 def is_process_running(binary, exact=False, full=False):
326  try:
327  args = ['pgrep']
328  if exact:
329  args.append('-x') # match exactly with the command name
330  if full:
331  args.append('-f') # use full process name to match
332  args.append(binary)
333  subprocess.check_output(args)
334  return True
335  except subprocess.CalledProcessError:
336  return False
337 
338 
339 @check('ArUco markers')
341  if is_process_running('aruco_detect', full=True):
342  try:
343  info('aruco_detect/length = %g m', rospy.get_param('aruco_detect/length'))
344  except KeyError:
345  failure('aruco_detect/length parameter is not set')
346  known_tilt = rospy.get_param('aruco_detect/known_tilt', '')
347  if known_tilt == 'map':
348  known_tilt += ' (ALL markers are on the floor)'
349  elif known_tilt == 'map_flipped':
350  known_tilt += ' (ALL markers are on the ceiling)'
351  info('aruco_detector/known_tilt = %s', known_tilt)
352  try:
353  rospy.wait_for_message('aruco_detect/markers', MarkerArray, timeout=1)
354  except rospy.ROSException:
355  failure('no markers detection')
356  return
357  else:
358  info('aruco_detect is not running')
359  return
360 
361  if is_process_running('aruco_map', full=True):
362  known_tilt = rospy.get_param('aruco_map/known_tilt', '')
363  if known_tilt == 'map':
364  known_tilt += ' (marker\'s map is on the floor)'
365  elif known_tilt == 'map_flipped':
366  known_tilt += ' (marker\'s map is on the ceiling)'
367  info('aruco_map/known_tilt = %s', known_tilt)
368 
369  try:
370  visualization = rospy.wait_for_message('aruco_map/visualization', VisualizationMarkerArray, timeout=1)
371  info('map has %s markers', len(visualization.markers))
372  except:
373  failure('cannot read aruco_map/visualization topic')
374 
375  try:
376  rospy.wait_for_message('aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
377  except rospy.ROSException:
378  failure('no map detection')
379  else:
380  info('aruco_map is not running')
381 
382 
383 @check('Vision position estimate')
384 def check_vpe():
385  vis = None
386  try:
387  vis = rospy.wait_for_message('mavros/vision_pose/pose', PoseStamped, timeout=1)
388  except rospy.ROSException:
389  try:
390  vis = rospy.wait_for_message('mavros/mocap/pose', PoseStamped, timeout=1)
391  except rospy.ROSException:
392  failure('no VPE or MoCap messages')
393  # check if vpe_publisher is running
394  try:
395  subprocess.check_output(['pgrep', '-x', 'vpe_publisher'])
396  except subprocess.CalledProcessError:
397  return # it's not running, skip following checks
398 
399  # check PX4 settings
400  est = get_param('SYS_MC_EST_GROUP')
401  if est == 1:
402  ext_yaw = get_param('ATT_EXT_HDG_M')
403  if ext_yaw != 1:
404  failure('vision yaw is disabled, change ATT_EXT_HDG_M parameter')
405  vision_yaw_w = get_param('ATT_W_EXT_HDG')
406  if vision_yaw_w == 0:
407  failure('vision yaw weight is zero, change ATT_W_EXT_HDG parameter')
408  else:
409  info('Vision yaw weight: %.2f', vision_yaw_w)
410  fuse = get_param('LPE_FUSION')
411  if not fuse & (1 << 2):
412  failure('vision position fusion is disabled, change LPE_FUSION parameter')
413  delay = get_param('LPE_VIS_DELAY')
414  if delay != 0:
415  failure('LPE_VIS_DELAY parameter is %s, but it should be zero', delay)
416  info('LPE_VIS_XY is %.2f m, LPE_VIS_Z is %.2f m', get_param('LPE_VIS_XY'), get_param('LPE_VIS_Z'))
417  elif est == 2:
418  fuse = get_param('EKF2_AID_MASK')
419  if not fuse & (1 << 3):
420  failure('vision position fusion is disabled, change EKF2_AID_MASK parameter')
421  if not fuse & (1 << 4):
422  failure('vision yaw fusion is disabled, change EKF2_AID_MASK parameter')
423  delay = get_param('EKF2_EV_DELAY')
424  if delay != 0:
425  failure('EKF2_EV_DELAY is %.2f, but it should be zero', delay)
426  info('EKF2_EVA_NOISE is %.3f, EKF2_EVP_NOISE is %.3f',
427  get_param('EKF2_EVA_NOISE'),
428  get_param('EKF2_EVP_NOISE'))
429 
430  if not vis:
431  return
432 
433  # check vision pose and estimated pose inconsistency
434  try:
435  pose = rospy.wait_for_message('mavros/local_position/pose', PoseStamped, timeout=1)
436  except:
437  return
438  horiz = math.hypot(vis.pose.position.x - pose.pose.position.x, vis.pose.position.y - pose.pose.position.y)
439  if horiz > 0.5:
440  failure('horizontal position inconsistency: %.2f m', horiz)
441  vert = vis.pose.position.z - pose.pose.position.z
442  if abs(vert) > 0.5:
443  failure('vertical position inconsistency: %.2f m', vert)
444  op = pose.pose.orientation
445  ov = vis.pose.orientation
446  yawp, _, _ = t.euler_from_quaternion((op.x, op.y, op.z, op.w), axes='rzyx')
447  yawv, _, _ = t.euler_from_quaternion((ov.x, ov.y, ov.z, ov.w), axes='rzyx')
448  yawdiff = yawp - yawv
449  yawdiff = math.degrees((yawdiff + 180) % 360 - 180)
450  if abs(yawdiff) > 8:
451  failure('yaw inconsistency: %.2f deg', yawdiff)
452 
453 
454 @check('Simple offboard node')
456  try:
457  rospy.wait_for_service('navigate', timeout=3)
458  rospy.wait_for_service('get_telemetry', timeout=3)
459  rospy.wait_for_service('land', timeout=3)
460  except rospy.ROSException:
461  failure('no simple_offboard services')
462 
463 
464 @check('IMU')
465 def check_imu():
466  try:
467  rospy.wait_for_message('mavros/imu/data', Imu, timeout=1)
468  except rospy.ROSException:
469  failure('no IMU data (check flight controller calibration)')
470 
471 
472 @check('Local position')
474  try:
475  pose = rospy.wait_for_message('mavros/local_position/pose', PoseStamped, timeout=1)
476  o = pose.pose.orientation
477  _, pitch, roll = t.euler_from_quaternion((o.x, o.y, o.z, o.w), axes='rzyx')
478  MAX_ANGLE = math.radians(2)
479  if abs(pitch) > MAX_ANGLE:
480  failure('pitch is %.2f deg; place copter horizontally or redo level horizon calib',
481  math.degrees(pitch))
482  if abs(roll) > MAX_ANGLE:
483  failure('roll is %.2f deg; place copter horizontally or redo level horizon calib',
484  math.degrees(roll))
485 
486  except rospy.ROSException:
487  failure('no local position')
488 
489 
490 @check('Velocity estimation')
492  try:
493  velocity = rospy.wait_for_message('mavros/local_position/velocity_local', TwistStamped, timeout=1)
494  horiz = math.hypot(velocity.twist.linear.x, velocity.twist.linear.y)
495  vert = velocity.twist.linear.z
496  if abs(horiz) > 0.1:
497  failure('horizontal velocity estimation is %.2f m/s; is copter staying still?' % horiz)
498  if abs(vert) > 0.1:
499  failure('vertical velocity estimation is %.2f m/s; is copter staying still?' % vert)
500 
501  velocity = rospy.wait_for_message('mavros/local_position/velocity_body', TwistStamped, timeout=1)
502  angular = velocity.twist.angular
503  ANGULAR_VELOCITY_LIMIT = 0.1
504  if abs(angular.x) > ANGULAR_VELOCITY_LIMIT:
505  failure('pitch rate estimation is %.2f rad/s (%.2f deg/s); is copter staying still?',
506  angular.x, math.degrees(angular.x))
507  if abs(angular.y) > ANGULAR_VELOCITY_LIMIT:
508  failure('pitch rate estimation is %.2f rad/s (%.2f deg/s); is copter staying still?',
509  angular.y, math.degrees(angular.y))
510  if abs(angular.z) > ANGULAR_VELOCITY_LIMIT:
511  failure('pitch rate estimation is %.2f rad/s (%.2f deg/s); is copter staying still?',
512  angular.z, math.degrees(angular.z))
513  except rospy.ROSException:
514  failure('no velocity estimation')
515 
516 
517 @check('Global position (GPS)')
519  try:
520  rospy.wait_for_message('mavros/global_position/global', NavSatFix, timeout=1)
521  except rospy.ROSException:
522  info('no global position')
523 
524 
525 @check('Optical flow')
527  # TODO:check FPS!
528  try:
529  rospy.wait_for_message('mavros/px4flow/raw/send', OpticalFlowRad, timeout=0.5)
530 
531  # check PX4 settings
532  rot = get_param('SENS_FLOW_ROT')
533  if rot != 0:
534  failure('SENS_FLOW_ROT parameter is %s, but it should be zero', rot)
535  est = get_param('SYS_MC_EST_GROUP')
536  if est == 1:
537  fuse = get_param('LPE_FUSION')
538  if not fuse & (1 << 1):
539  failure('optical flow fusion is disabled, change LPE_FUSION parameter')
540  if not fuse & (1 << 1):
541  failure('flow gyro compensation is disabled, change LPE_FUSION parameter')
542  scale = get_param('LPE_FLW_SCALE')
543  if not numpy.isclose(scale, 1.0):
544  failure('LPE_FLW_SCALE parameter is %.2f, but it should be 1.0', scale)
545 
546  info('LPE_FLW_QMIN is %s, LPE_FLW_R is %.4f, LPE_FLW_RR is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
547  get_param('LPE_FLW_QMIN'),
548  get_param('LPE_FLW_R'),
549  get_param('LPE_FLW_RR'),
550  get_param('SENS_FLOW_MINHGT'),
551  get_param('SENS_FLOW_MAXHGT'))
552  elif est == 2:
553  fuse = get_param('EKF2_AID_MASK')
554  if not fuse & (1 << 1):
555  failure('optical flow fusion is disabled, change EKF2_AID_MASK parameter')
556  delay = get_param('EKF2_OF_DELAY')
557  if delay != 0:
558  failure('EKF2_OF_DELAY is %.2f, but it should be zero', delay)
559  info('EKF2_OF_QMIN is %s, EKF2_OF_N_MIN is %.4f, EKF2_OF_N_MAX is %.4f, SENS_FLOW_MINHGT is %.3f, SENS_FLOW_MAXHGT is %.3f',
560  get_param('EKF2_OF_QMIN'),
561  get_param('EKF2_OF_N_MIN'),
562  get_param('EKF2_OF_N_MAX'),
563  get_param('SENS_FLOW_MINHGT'),
564  get_param('SENS_FLOW_MAXHGT'))
565 
566  except rospy.ROSException:
567  failure('no optical flow data (from Raspberry)')
568 
569 
570 @check('Rangefinder')
572  # TODO: check FPS!
573  rng = False
574  try:
575  rospy.wait_for_message('rangefinder/range', Range, timeout=4)
576  rng = True
577  except rospy.ROSException:
578  failure('no rangefinder data from Raspberry')
579 
580  try:
581  rospy.wait_for_message('mavros/distance_sensor/rangefinder', Range, timeout=4)
582  rng = True
583  except rospy.ROSException:
584  failure('no rangefinder data from PX4')
585 
586  if not rng:
587  return
588 
589  est = get_param('SYS_MC_EST_GROUP')
590  if est == 1:
591  fuse = get_param('LPE_FUSION')
592  if not fuse & (1 << 5):
593  info('"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
594  else:
595  info('"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
596 
597  elif est == 2:
598  hgt = get_param('EKF2_HGT_MODE')
599  if hgt != 2:
600  info('EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
601  else:
602  info('EKF2_HGT_MODE = Range sensor, operating over flat surface')
603  aid = get_param('EKF2_RNG_AID')
604  if aid != 1:
605  info('EKF2_RNG_AID != 1, range sensor aiding disabled')
606  else:
607  info('EKF2_RNG_AID = 1, range sensor aiding enabled')
608 
609 
610 @check('Boot duration')
612  output = subprocess.check_output('systemd-analyze')
613  r = re.compile(r'([\d\.]+)s\s*$', flags=re.MULTILINE)
614  duration = float(r.search(output).groups()[0])
615  if duration > 15:
616  failure('long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
617 
618 
619 @check('CPU usage')
621  WHITELIST = 'nodelet',
622  CMD = "top -n 1 -b -i | tail -n +8 | awk '{ printf(\"%-8s\\t%-8s\\t%-8s\\n\", $1, $9, $12); }'"
623  output = subprocess.check_output(CMD, shell=True)
624  processes = output.split('\n')
625  for process in processes:
626  if not process:
627  continue
628  pid, cpu, cmd = process.split('\t')
629 
630  if cmd.strip() not in WHITELIST and float(cpu) > 30:
631  failure('high CPU usage (%s%%) detected: %s (PID %s)',
632  cpu.strip(), cmd.strip(), pid.strip())
633 
634 
635 @check('clover.service')
637  try:
638  output = subprocess.check_output('systemctl show -p ActiveState --value clover.service'.split(),
639  stderr=subprocess.STDOUT)
640  except subprocess.CalledProcessError as e:
641  failure('systemctl returned %s: %s', e.returncode, e.output)
642  return
643  if 'inactive' in output:
644  failure('service is not running, try sudo systemctl restart clover')
645  return
646  elif 'failed' in output:
647  failure('service failed to run, check your launch-files')
648 
649  r = re.compile(r'^(.*)\[(FATAL|ERROR)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
650  error_count = OrderedDict()
651  try:
652  for line in open('/tmp/clover.err', 'r'):
653  node_error = r.search(line)
654  if node_error:
655  msg = node_error.groups()[1] + ': ' + node_error.groups()[2]
656  if msg in error_count:
657  error_count[msg] += 1
658  else:
659  error_count.update({msg: 1})
660  else:
661  error_count.update({line.strip(): 1})
662 
663  for error in error_count:
664  if error_count[error] == 1:
665  failure(error)
666  else:
667  failure('%s (%d)', error, error_count[error])
668 
669  except IOError as e:
670  failure('%s', e)
671 
672 
673 @check('Image')
675  try:
676  info('version: %s', open('/etc/clover_version').read().strip())
677  except IOError:
678  info('no /etc/clover_version file, not the Clover image?')
679 
680 
681 @check('Preflight status')
683  # Make sure the console is available to us
684  mavlink_exec('\n')
685  cmdr_output = mavlink_exec('commander check')
686  if cmdr_output == '':
687  failure('no data from FCU')
688  return
689  cmdr_lines = cmdr_output.split('\n')
690  r = re.compile(r'^(.*)(Preflight|Prearm) check: (.*)')
691  for line in cmdr_lines:
692  if 'WARN' in line:
693  failure(line[line.find(']') + 2:])
694  continue
695  match = r.search(line)
696  if match is not None:
697  check_status = match.groups()[2]
698  if check_status != 'OK':
699  failure(' '.join([match.groups()[1], 'check:', check_status]))
700 
701 
702 @check('Network')
704  ros_hostname = os.environ.get('ROS_HOSTNAME', '').strip()
705 
706  if not ros_hostname:
707  failure('no ROS_HOSTNAME is set')
708 
709  elif ros_hostname.endswith('.local'):
710  # using mdns hostname
711  hosts = open('/etc/hosts', 'r')
712  for line in hosts:
713  parts = line.split()
714  if len(parts) < 2:
715  continue
716  ip = parts.pop(0).split('.')
717  if ip[0] == '127': # loopback ip
718  if ros_hostname in parts:
719  break
720  else:
721  failure('not found %s in /etc/hosts, ROS will malfunction if network interfaces are down, https://clover.coex.tech/hostname', ros_hostname)
722 
723 
724 @check('RPi health')
726  # `vcgencmd get_throttled` output codes taken from
727  # https://github.com/raspberrypi/documentation/blob/JamesH65-patch-vcgencmd-vcdbg-docs/raspbian/applications/vcgencmd.md#get_throttled
728  # TODO: support more base platforms?
729  FLAG_UNDERVOLTAGE_NOW = 0x1
730  FLAG_FREQ_CAP_NOW = 0x2
731  FLAG_THROTTLING_NOW = 0x4
732  FLAG_THERMAL_LIMIT_NOW = 0x8
733  FLAG_UNDERVOLTAGE_OCCURRED = 0x10000
734  FLAG_FREQ_CAP_OCCURRED = 0x20000
735  FLAG_THROTTLING_OCCURRED = 0x40000
736  FLAG_THERMAL_LIMIT_OCCURRED = 0x80000
737 
738  FLAG_DESCRIPTIONS = (
739  (FLAG_THROTTLING_NOW, 'system throttled to prevent damage'),
740  (FLAG_THROTTLING_OCCURRED, 'your system is susceptible to throttling'),
741  (FLAG_UNDERVOLTAGE_NOW, 'not enough power for onboard computer, flight inadvisable'),
742  (FLAG_UNDERVOLTAGE_OCCURRED, 'power supply cannot provide enough power'),
743  (FLAG_FREQ_CAP_NOW, 'CPU reached thermal limit and is throttled now'),
744  (FLAG_FREQ_CAP_OCCURRED, 'CPU may overheat during drone operation, consider additional cooling'),
745  (FLAG_THERMAL_LIMIT_NOW, 'CPU reached soft thermal limit, frequency reduced'),
746  (FLAG_THERMAL_LIMIT_OCCURRED, 'CPU may reach soft thermal limit, consider additional cooling'),
747  )
748 
749  try:
750  # vcgencmd outputs a single string in a form of
751  # <parameter>=<value>
752  # In case of `get_throttled`, <value> is a hexadecimal number
753  # with some of the FLAGs OR'ed together
754  output = subprocess.check_output(['vcgencmd', 'get_throttled'])
755  except OSError:
756  failure('could not call vcgencmd binary; not a Raspberry Pi?')
757  return
758 
759  throttle_mask = int(output.split('=')[1], base=16)
760  for flag_description in FLAG_DESCRIPTIONS:
761  if throttle_mask & flag_description[0]:
762  failure(flag_description[1])
763 
764 
765 @check('Board')
767  try:
768  info('%s', open('/proc/device-tree/model').readline())
769  except IOError:
770  info('could not open /proc/device-tree/model, not a Raspberry Pi?')
771 
772 
773 def selfcheck():
774  check_image()
775  check_board()
777  check_network()
778  check_fcu()
779  check_imu()
785  check_aruco()
788  check_vpe()
793 
794 
795 if __name__ == '__main__':
796  rospy.loginfo('Performing selfcheck...')
797  selfcheck()
def check_local_position()
Definition: selfcheck.py:473
def check_fcu()
Definition: selfcheck.py:189
def check_imu()
Definition: selfcheck.py:465
def check_board()
Definition: selfcheck.py:766
def check_camera(name)
Definition: selfcheck.py:284
def is_process_running(binary, exact=False, full=False)
Definition: selfcheck.py:325
def selfcheck()
Definition: selfcheck.py:773
def check_aruco()
Definition: selfcheck.py:340
def get_param(name)
Definition: selfcheck.py:90
def failure(text, args)
Definition: selfcheck.py:56
ssize_t len
def describe_direction(v)
Definition: selfcheck.py:267
def check_optical_flow()
Definition: selfcheck.py:526
def check_clover_service()
Definition: selfcheck.py:636
def check_boot_duration()
Definition: selfcheck.py:611
def check_main_camera()
Definition: selfcheck.py:321
def check_rangefinder()
Definition: selfcheck.py:571
def mavlink_message_handler(msg)
Definition: selfcheck.py:111
def check_vpe()
Definition: selfcheck.py:384
def check_image()
Definition: selfcheck.py:674
def mavlink_exec(cmd, timeout=3.0)
Definition: selfcheck.py:128
def check(name)
Definition: selfcheck.py:68
def check_cpu_usage()
Definition: selfcheck.py:620
def check_velocity()
Definition: selfcheck.py:491
def check_rpi_health()
Definition: selfcheck.py:725
def check_simpleoffboard()
Definition: selfcheck.py:455
def info(text, args)
Definition: selfcheck.py:62
def check_network()
Definition: selfcheck.py:703
def check_global_position()
Definition: selfcheck.py:518
def check_preflight_status()
Definition: selfcheck.py:682


clover
Author(s): Oleg Kalachev , Artem Smirnov
autogenerated on Mon Feb 28 2022 22:08:29