16 from collections
import OrderedDict
18 from threading
import Event
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
44 rospy.init_node(
'selfcheck')
58 rospy.logwarn(
'%s: %s', current_check, msg)
64 rospy.loginfo(
'%s: %s', current_check, msg)
70 def wrapper(*args, **kwargs):
77 except Exception
as e:
79 rospy.logerr(
'%s: exception occurred', name)
81 if not failures
and not infos:
82 rospy.loginfo(
'%s: OK', name)
87 param_get = rospy.ServiceProxy(
'mavros/param/get', ParamGet)
93 except rospy.ServiceException
as e:
98 failure(
'unable to retrieve PX4 parameter %s', name)
100 if res.value.integer != 0:
101 return res.value.integer
102 return res.value.real
106 link = mavutil.mavlink.MAVLink(
'', 255, 1)
107 mavlink_pub = rospy.Publisher(
'mavlink/to', Mavlink, queue_size=1)
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:
119 mavlink_recv = mavlink_recv[:mavlink_recv.find(
'nsh>') - 1]
123 mavlink_sub = rospy.Subscriber(
'mavlink/from', Mavlink, mavlink_message_handler)
132 if not cmd.endswith(
'\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,
141 data=map(ord, cmd.ljust(70,
'\0')))
143 ros_msg = mavlink.convert_to_rosmsg(msg)
144 mavlink_pub.publish(ros_msg)
145 recv_event.wait(timeout)
159 9:
'roll 180°, yaw 45°',
160 10:
'roll 180°, yaw 90°',
161 11:
'roll 180°, yaw 135°',
163 13:
'roll 180°, yaw 225°',
164 14:
'roll 180°, yaw 270°',
165 15:
'roll 180°, yaw 315°',
167 17:
'roll 90°, yaw 45°',
168 18:
'roll 90°, yaw 90°',
169 19:
'roll 90°, yaw 135°',
171 21:
'roll 270°, yaw 45°',
172 22:
'roll 270°, yaw 90°',
173 23:
'roll 270°, yaw 135°',
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°',
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)')
199 if version_str ==
'':
200 info(
'no version data available from SITL')
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 212 if not is_clover_firmware:
213 failure(
'not running Clover PX4 firmware, https://clover.coex.tech/firmware')
217 info(
'selected estimator: LPE')
220 info(
'LPE_FUSION: land detector fusion is enabled')
222 info(
'LPE_FUSION: land detector fusion is disabled')
224 info(
'LPE_FUSION: barometer fusion is enabled')
226 info(
'LPE_FUSION: barometer fusion is disabled')
230 info(
'magnetometer weight (ATT_W_MAG) is zero, better for indoor flights')
232 info(
'magnetometer weight (ATT_W_MAG) is non-zero (%.2f), better for outdoor flights', mag_yaw_w)
235 info(
'selected estimator: EKF2')
237 failure(
'unknown selected estimator: %s', est)
242 info(
'board rotation: %s', BOARD_ROTATIONS[rot])
244 failure(
'unknown board rotation %s', rot)
247 if cbrk_usb_chk != 197848:
248 failure(
'set parameter CBRK_USB_CHK to 197848 for flying with USB connected')
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')
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)
259 failure(
'critically low cell voltage: %.2f V, recharge battery', cell)
260 except rospy.ROSException:
263 except rospy.ROSException:
264 failure(
'no MAVROS state (check wiring)')
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)
291 camera_info = rospy.wait_for_message(name +
'/camera_info', CameraInfo, timeout=1)
292 except rospy.ROSException:
293 failure(
'%s: no calibration info', name)
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)
302 optical = Vector3Stamped()
303 optical.header.frame_id = img.header.frame_id
305 cable = Vector3Stamped()
306 cable.header.frame_id = img.header.frame_id
311 if not optical
or not cable:
312 info(
'%s: custom camera orientation detected', name)
314 info(
'camera is oriented %s, cable from camera goes %s', optical, cable)
316 except tf2_ros.TransformException:
317 failure(
'cannot transform from base_link to camera frame')
320 @
check(
'Main camera')
333 subprocess.check_output(args)
335 except subprocess.CalledProcessError:
339 @
check(
'ArUco markers')
343 info(
'aruco_detect/length = %g m', rospy.get_param(
'aruco_detect/length'))
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)
353 rospy.wait_for_message(
'aruco_detect/markers', MarkerArray, timeout=1)
354 except rospy.ROSException:
355 failure(
'no markers detection')
358 info(
'aruco_detect is not running')
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)
370 visualization = rospy.wait_for_message(
'aruco_map/visualization', VisualizationMarkerArray, timeout=1)
371 info(
'map has %s markers',
len(visualization.markers))
373 failure(
'cannot read aruco_map/visualization topic')
376 rospy.wait_for_message(
'aruco_map/pose', PoseWithCovarianceStamped, timeout=1)
377 except rospy.ROSException:
380 info(
'aruco_map is not running')
383 @
check(
'Vision position estimate')
387 vis = rospy.wait_for_message(
'mavros/vision_pose/pose', PoseStamped, timeout=1)
388 except rospy.ROSException:
390 vis = rospy.wait_for_message(
'mavros/mocap/pose', PoseStamped, timeout=1)
391 except rospy.ROSException:
392 failure(
'no VPE or MoCap messages')
395 subprocess.check_output([
'pgrep',
'-x',
'vpe_publisher'])
396 except subprocess.CalledProcessError:
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')
409 info(
'Vision yaw weight: %.2f', vision_yaw_w)
411 if not fuse & (1 << 2):
412 failure(
'vision position fusion is disabled, change LPE_FUSION parameter')
415 failure(
'LPE_VIS_DELAY parameter is %s, but it should be zero', delay)
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')
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',
435 pose = rospy.wait_for_message(
'mavros/local_position/pose', PoseStamped, timeout=1)
438 horiz = math.hypot(vis.pose.position.x - pose.pose.position.x, vis.pose.position.y - pose.pose.position.y)
440 failure(
'horizontal position inconsistency: %.2f m', horiz)
441 vert = vis.pose.position.z - pose.pose.position.z
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)
451 failure(
'yaw inconsistency: %.2f deg', yawdiff)
454 @
check(
'Simple offboard node')
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')
467 rospy.wait_for_message(
'mavros/imu/data', Imu, timeout=1)
468 except rospy.ROSException:
469 failure(
'no IMU data (check flight controller calibration)')
472 @
check(
'Local position')
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',
482 if abs(roll) > MAX_ANGLE:
483 failure(
'roll is %.2f deg; place copter horizontally or redo level horizon calib',
486 except rospy.ROSException:
490 @
check(
'Velocity estimation')
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
497 failure(
'horizontal velocity estimation is %.2f m/s; is copter staying still?' % horiz)
499 failure(
'vertical velocity estimation is %.2f m/s; is copter staying still?' % vert)
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')
517 @
check(
'Global position (GPS)')
520 rospy.wait_for_message(
'mavros/global_position/global', NavSatFix, timeout=1)
521 except rospy.ROSException:
522 info(
'no global position')
525 @
check(
'Optical flow')
529 rospy.wait_for_message(
'mavros/px4flow/raw/send', OpticalFlowRad, timeout=0.5)
534 failure(
'SENS_FLOW_ROT parameter is %s, but it should be zero', rot)
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')
543 if not numpy.isclose(scale, 1.0):
544 failure(
'LPE_FLW_SCALE parameter is %.2f, but it should be 1.0', scale)
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',
554 if not fuse & (1 << 1):
555 failure(
'optical flow fusion is disabled, change EKF2_AID_MASK parameter')
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',
566 except rospy.ROSException:
567 failure(
'no optical flow data (from Raspberry)')
570 @
check(
'Rangefinder')
575 rospy.wait_for_message(
'rangefinder/range', Range, timeout=4)
577 except rospy.ROSException:
578 failure(
'no rangefinder data from Raspberry')
581 rospy.wait_for_message(
'mavros/distance_sensor/rangefinder', Range, timeout=4)
583 except rospy.ROSException:
584 failure(
'no rangefinder data from PX4')
592 if not fuse & (1 << 5):
593 info(
'"pub agl as lpos down" in LPE_FUSION is disabled, NOT operating over flat surface')
595 info(
'"pub agl as lpos down" in LPE_FUSION is enabled, operating over flat surface')
600 info(
'EKF2_HGT_MODE != Range sensor, NOT operating over flat surface')
602 info(
'EKF2_HGT_MODE = Range sensor, operating over flat surface')
605 info(
'EKF2_RNG_AID != 1, range sensor aiding disabled')
607 info(
'EKF2_RNG_AID = 1, range sensor aiding enabled')
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])
616 failure(
'long Raspbian boot duration: %ss (systemd-analyze for analyzing)', duration)
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:
628 pid, cpu, cmd = process.split(
'\t')
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())
635 @
check(
'clover.service')
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)
643 if 'inactive' in output:
644 failure(
'service is not running, try sudo systemctl restart clover')
646 elif 'failed' in output:
647 failure(
'service failed to run, check your launch-files')
649 r = re.compile(
r'^(.*)\[(FATAL|ERROR)\] \[\d+.\d+\]: (.*?)(\x1b(.*))?$')
650 error_count = OrderedDict()
652 for line
in open(
'/tmp/clover.err',
'r'): 653 node_error = r.search(line) 655 msg = node_error.groups()[1] +
': ' + node_error.groups()[2]
656 if msg
in error_count:
657 error_count[msg] += 1
659 error_count.update({msg: 1})
661 error_count.update({line.strip(): 1})
663 for error
in error_count:
664 if error_count[error] == 1:
667 failure(
'%s (%d)', error, error_count[error])
676 info(
'version: %s', open(
'/etc/clover_version').read().strip())
678 info(
'no /etc/clover_version file, not the Clover image?')
681 @
check(
'Preflight status')
686 if cmdr_output ==
'':
689 cmdr_lines = cmdr_output.split(
'\n')
690 r = re.compile(
r'^(.*)(Preflight|Prearm) check: (.*)')
691 for line
in cmdr_lines:
693 failure(line[line.find(
']') + 2:])
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]))
704 ros_hostname = os.environ.get(
'ROS_HOSTNAME',
'').strip()
707 failure(
'no ROS_HOSTNAME is set')
709 elif ros_hostname.endswith(
'.local'):
711 hosts = open(
'/etc/hosts',
'r') 716 ip = parts.pop(0).split(
'.')
718 if ros_hostname
in parts:
721 failure(
'not found %s in /etc/hosts, ROS will malfunction if network interfaces are down, https://clover.coex.tech/hostname', ros_hostname)
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
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'),
754 output = subprocess.check_output([
'vcgencmd',
'get_throttled'])
756 failure(
'could not call vcgencmd binary; not a Raspberry Pi?')
759 throttle_mask = int(output.split(
'=')[1], base=16)
760 for flag_description
in FLAG_DESCRIPTIONS:
761 if throttle_mask & flag_description[0]:
768 info(
'%s', open(
'/proc/device-tree/model').readline())
770 info(
'could not open /proc/device-tree/model, not a Raspberry Pi?')
795 if __name__ ==
'__main__':
796 rospy.loginfo(
'Performing selfcheck...')
def check_local_position()
def is_process_running(binary, exact=False, full=False)
def describe_direction(v)
def check_clover_service()
def check_boot_duration()
def mavlink_message_handler(msg)
def mavlink_exec(cmd, timeout=3.0)
def check_simpleoffboard()
def check_global_position()
def check_preflight_status()