-
Notifications
You must be signed in to change notification settings - Fork 2
Configuration:Safety
The takeoff and landing detector is a module to
- detect the flatness before takeoff
- detect a successful takeoff
- detect a landing
Currently, for full functionality, this module requires at least 1 IMU and 1 AGL (e.g., LRF) or 1 pressure sensor (less accurate). All configuration parameters are set in the safety launchfile src/flightstack/flightstack_bringup/launch/fs_safety.launch
-
toland_imu
: topic for the IMU -
toland_agl
: topic for the AGL sensor, e.g. lrf -
angle_threshold
: threshold for violating "ground flatness" -
distance_threshold
: threshold for violating "being on ground" (due to sensor mounting)
Further launch parameters, e.g. sensor calibration, can also be added there.
The esimator supervisor is a small node to check if the state estimator is diverging pre-takeoff. It calculates the mean of all measurements received, while assuming the vehicle is in static condition, and calculates the norm distance of each pose to the mean. If the do not differ higher than a set threshold, the estimator is considered working. The only parameters to be set within the src/flightstack/flightstack_bringup/launch/fs_safety.launch
are
-
topic_to_supervise
a pose published by the estimator, by default it uses the/mavros/vision_pose/pose
topic -
window_s
duration to check the estimates and thus divergence -
max_norm
maximum metric distance (for position) allowed to be deviated from mean
The watchdog needs to have a full list of information about the entities to watch. Since it is mostly used to detect if sensors are working, please also refer to the sensor configuration tutorial.
The watchod has two parameters to be set safety launchfile src/flightstack/flightstack_bringup/launch/fs_safety.launch
-
watchdog_check_dt
the time period used for checking in seconds (=1.0/check_frequency
). If you experience performance issues when using the watchdog please increase the checking time period. -
watchdog_verbose
to enable debug output to the console
The watchdog also requires three configuration files, set as launch parameters:
-
watchdog_drivers_cfg_file
configuration file for (re-)starting drivers -
watchdog_topics_cfg_file
configuration for ROS topics to watch -
watchdog_nodes_cfg_file
configuration for ROS nodes to watch
By default, the launch configuration should point to the config/watchdog/*.yaml
inside the bringup
of your flight stack configuration.
Each of the configuration files provides information about the entities to watch, as well as actions to perform, if requested by the autonomy. Make sure that the entity_id
is persistent throughout the configuration files.
The drivers configuration is for watchdog entities that need to execute system calls (i.e. a bash script checking a service).
# use the exact same name as in nodes.ini and topics.ini for value "driver_name"
gnss_driver:
# name of the entity
entity_id: gnss_sensor
# path to script where the checking happens
check_script: /${HOME}/flightstack_cws/src/flightstack/flightstack_scripts/driver_scripts/gnss_check.sh
# path to script where the restarting happens
restart_script: /${HOME}/flightstack_cws/src/flightstack/flightstack_scripts/driver_scripts/gnss_restart.sh
The check_script
is executed at the watchdog rate, and should return 0
(if everything is working) or non-zero if a fault is detected. An examplatory script to check if a realsense device is connected is found here.
When a failure is detected (either through the corresponding entity at ROS topic/node level or driver level), the restart_script
is executed to restart the driver. A sample script using uhubctl
to re-power the usb hub (main cause of realsense failures) can be found here. Please note that a restart is only performed on request by the autonomy engine and requires an entity action level of hold
(otherwise the vehicle would continue or land).
The ROS nodes configuration list all node entities that should be checked and links action items if the topic reports issues.
# use the node name (exactly as in the ROS workspace for the entry)
/gnss:
# name of the entity
entity_id: gnss_sensor
# name of the driver entity associated with it
driver_name: gnss_driver
max_restart_attempts: 0
restart_timeout: 1
The /<node_name>
entry needs to be exactly the same as the node is named within the ROS universe.
The max_restart_attempts
defines the number of times an entity can be restarted, without it resulting in a critical failure (raised level for the autonomy engine, will result in a landing except if the entity is ignored).
The restart_timeout
is the time in seconds an entity has to return to full functionality after a restart was attempted, before triggering another failure.
The ROS topics configuration lists all ROS topics that should be listened to.
# use the topic name (exactly as in the ROS workspace for the entry)
/gnss/fix:
# name of the entity
entity_id: gnss_sensor
# expected frequency [in HZ]
rate: 100
# rate delta allowed for non-critical failure [relative to rate]
margin: 0.1
# number of messages used to check the rate
window: 100
# severity level of failure
severity: 0 # deprecated
# name of the rosnode associated with it
node_name: /gnss # same as in 'nodes.yaml'
# name of the driver associated with it
driver_name: gnss_driver # same as in 'drivers.yaml'
Similar to the node entry, /<node_name>/<topic_name>
should make the topic to watch within the ROS universe exactly.
rate
defines the expected rate the messages on the topic should have, with the parameter margin
defining the deviation until which the rate is considered as acceptable (due to bandwith, calculating errors, etc.). In the above example for any topic rate above 90 Hz the sensor is considered as working normally.
The window
defines the number of messages used to derive the rate. Ideally this should not be lower than watchdog_check_dt*rate
(i.e. the number of expected messages within the check rate).
The node_name
and driver_name
determine the corresponding ROS node and driver entry. This values are needed in case the sensor driver or ROS node needs to be restarted. Further, this allows the definition of multiple ROS topics all belonging to the same ROS node.