diff --git a/config/worlds/world_cisar.yaml b/config/worlds/world_cisar.yaml index a50d677..653619f 100644 --- a/config/worlds/world_cisar.yaml +++ b/config/worlds/world_cisar.yaml @@ -65,5 +65,5 @@ safety_area: # the frame of reference in which the max&min z is expressed frame_name: "world_origin" - max_z: 8.0 + max_z: 25.0 min_z: 1.0 diff --git a/config/worlds/world_kn_yard.yaml b/config/worlds/world_kn_yard.yaml index 612b65b..8558777 100644 --- a/config/worlds/world_kn_yard.yaml +++ b/config/worlds/world_kn_yard.yaml @@ -30,5 +30,5 @@ safety_area: # the frame of reference in which the max&min z is expressed frame_name: "world_origin" - max_z: 4.0 + max_z: 8.0 min_z: 1.0 diff --git a/tmux/robofly/config/custom_config.yaml b/tmux/robofly/config/custom_config.yaml new file mode 100644 index 0000000..aeac36b --- /dev/null +++ b/tmux/robofly/config/custom_config.yaml @@ -0,0 +1,289 @@ +mrs_uav_managers: + + control_manager: + Se3Controller: + eland_threshold: 2.5 + failsafe_threshold: 3.5 + + constraint_manager: + + estimator_types: [ + "open_vins", + "gps_baro", + ] + + constraints: [ + "slow", + "medium", + "fast" + ] + + # list of allowed gains per odometry mode + allowed_constraints: + gps_baro: ["slow", "medium", "fast"] + open_vins: ["slow", "medium", "fast"] + + constraints: [ + "slow", + "medium", + "fast", + ] + + allowed_constraints: + gps_baro: ["slow", "medium", "fast"] + + default_constraints: + gps_baro: "medium" + open_vins: "medium" + + estimation_manager: + + # loaded state estimator plugins + # available in mrs_uav_state_estimators: gps_garmin, gps_baro, rtk, aloam, ground_truth, dummy + state_estimators: [ + "gps_baro", + "open_vins", + ] + + initial_state_estimator: "gps_baro" # will be used as the first state estimator + agl_height_estimator: "" # only slightly filtered height for checking min height (not used in control feedback) + + gps_baro: # namespace of the state estimator + + alt_baro: # namespace of the altitude estimator + + process_noise: # process noise covariance (Q) + pos: 1.0 # position state + vel: 10.0 # velocity state + acc: 100.0 # acceleration state + + corrections: [ + # positional correction only makes the estimator unstable, vel_hw_api is not a derivative of pos_hw_api, vel_hw_api_only works best + "pos_hw_api" + ] + + pos_hw_api: + state_id: 0 # 0 - position, 1 - velocity, 2 - acceleration + noise: 0.001 # measurement noise covariance (R) + noise_unhealthy_coeff: 100.0 # covariance gets multiplied by this coefficient when correction is unhealthy (R) + message: + type: "geometry_msgs/PointStamped" + topic: "hw_api/position" # without uav namespace + limit: + delay: 1.0 # [s] messages with higher delay will flag correction as unhealthy + time_since_last: 0.5 # [s] larger time step between messages will flag correction as unhealthy + + processors: [] # types of processors attached to this measurement + + # namespace of the state estimator + open_vins: + + address: "open_vins/OpenVinsEstimatorPlugin" + + requires: # data required from the hw api + gnss: false + imu: false + distance_sensor: false + altitude: false + magnetometer_heading: false + position: false + orientation: true + velocity: true + angular_velocity: true + + override_frame_id: # override the default frame_id with a custom one + enabled: true + frame_id: "vio_origin" # the desired frame_id without the UAV namespace + + estimators: # the names of the partial estimators + lateral: + name: "lat_open_vins" + altitude: + name: "alt_open_vins" + # name: "alt_garmin" + heading: + name: "hdg_open_vins" + passthrough: false # if true, then heading is not estimated but passed through from the orientation topic + + topics: + orientation: "hw_api/orientation" # orientation passthrough + angular_velocity: "hw_api/angular_velocity" # angular velocity passthrough + + # namespace of the altitude estimator + alt_open_vins: # namespace of the altitude estimator + + max_flight_z: 100.0 # [m] maximum allowed flight Z (in the estimator frame) + + innovation: + limit: 1.0 # [m] innovation limit that will trigger action + action: "switch" # {"eland", "switch", "mitigate"} + + repredictor: # repredictor for correct fusion of delayed measurements + enabled: true + buffer_size: 200 # [samples] how many states and corrections are kept in history (i.e. estimator running at the default 100 Hz rate will be able to fuse corrections with up to 2 s delay with buffer size of 200 samples) + + process_noise: # process noise covariance (Q) + pos: 1.0 # position state + vel: 100.0 # velocity state + acc: 100.0 # acceleration state + + corrections: [ + "pos_vio", + "vel_hw_api" + ] + + pos_vio: + state_id: 0 # 0 - position, 1 - velocity, 2 - acceleration + noise: 0.001 # measurement noise covariance (R) + noise_unhealthy_coeff: 100.0 # covariance gets multiplied by this coefficient when correction is unhealthy (R) + message: + type: "nav_msgs/Odometry" + topic: "vins_republisher/odom" # without uav namespace + limit: + delay: 1.0 # [s] messages with higher delay will flag correction as unhealthy + time_since_last: 0.5 # [s] larger time step between messages will flag correction as unhealthy + + processors: [] # types of processors attached to this measurement + + vel_hw_api: + state_id: 1 # 0 - position, 1 - velocity, 2 - acceleration + noise: 1.0 # measurement noise covariance (R) + noise_unhealthy_coeff: 100.0 # covariance gets multiplied by this coefficient when correction is unhealthy (R) + message: + type: "geometry_msgs/Vector3Stamped" + topic: "hw_api/velocity" # without uav namespace + limit: + delay: 1.0 # [s] messages with higher delay will flag correction as unhealthy + time_since_last: 0.5 # [s] larger time step between messages will flag correction as unhealthy + + processors: [] # types of processors attached to this measurement + + median_filter: + buffer_size: 20 # the number of samples from which the median is calculated + max_diff: 2.0 # [m] reject measurement if difference from median is over this value + + + # namespace of the heading estimator + hdg_open_vins: # namespace of the heading estimator + + max_flight_z: 100.0 # [m] maximum allowed flight Z (in the estimator frame) + + position_innovation_limit: 1.0 # [rad] innovation limit that will trigger switch to other estimator + + repredictor: # repredictor for correct fusion of delayed measurements + enabled: true + buffer_size: 200 # [samples] how many states and corrections are kept in history (i.e. estimator running at the default 100 Hz rate will be able to fuse corrections with up to 2 s delay with buffer size of 200 samples) + + process_noise: # process noise covariance (Q) + pos: 0.1 # position state + vel: 0.1 # velocity state + + corrections: [ + "hdg_vio" + ] + + hdg_vio: + state_id: 0 # 0 - position, 1 - velocity, 2 - acceleration + noise: 0.0001 # measurement noise covariance (R) + noise_unhealthy_coeff: 100.0 # covariance gets multiplied by this coefficient when correction is unhealthy (R) + message: + type: "nav_msgs/Odometry" + topic: "vins_republisher/odom" # without uav namespace + limit: + delay: 1.0 # [s] messages with higher delay will flag correction as unhealthy + time_since_last: 0.5 # [s] larger time step between messages will flag correction as unhealthy + + processors: [] # types of processors attached to this measurement + + # namespace of the lateral estimator + lat_open_vins: # namespace of the lateral estimator + + hdg_source_topic: "vio/hdg_vio/output" # [mrs_uav_state_estimation/EstimatorOutput] + + max_flight_z: 100.0 # [m] maximum allowed flight Z (in the estimator frame) + + innovation: + limit: 1.0 # [m] innovation limit that will trigger action + action: "eland" # {"eland", "switch", "mitigate"} + + repredictor: # repredictor for correct fusion of delayed measurements + enabled: true + buffer_size: 200 # [samples] how many states and corrections are kept in history (i.e. estimator running at the default 100 Hz rate will be able to fuse corrections with up to 2 s delay with buffer size of 200 samples) + + process_noise: # process noise covariance (Q) + pos: 0.1 # position state + vel: 1.0 # velocity state + acc: 1.0 # acceleration state + + corrections: [ + "pos_vio", + "vel_vio" + ] + + pos_vio: + state_id: 0 # 0 - position, 1 - velocity, 2 - acceleration + noise: 0.01 # measurement noise covariance (R) + noise_unhealthy_coeff: 100.0 # covariance gets multiplied by this coefficient when correction is unhealthy (R) + message: + type: "nav_msgs/Odometry" + topic: "vins_republisher/odom" # without uav namespace + limit: + delay: 1.0 # [s] messages with higher delay will flag correction as unhealthy + time_since_last: 0.5 # [s] larger time step between messages will flag correction as unhealthy + + processors: [] # types of processors attached to this measurement + + vel_vio: + state_id: 1 # 0 - position, 1 - velocity, 2 - acceleration + noise: 0.01 # measurement noise covariance (R) + noise_unhealthy_coeff: 100.0 # covariance gets multiplied by this coefficient when correction is unhealthy (R) + body_frame: true # velocity is in body frame from open_vins + message: + type: "nav_msgs/Odometry" + topic: "vins_republisher/odom" # without uav namespace + limit: + delay: 1.0 # [s] messages with higher delay will flag correction as unhealthy + time_since_last: 0.5 # [s] larger time step between messages will flag correction as unhealthy + + processors: [] # types of processors attached to this measurement + + uav_manager: + + takeoff: + + during_takeoff: + + controller: "MpcController" + + after_takeoff: + + controller: "MpcController" + + takeoff_height: 0.8 + + midair_activation: + after_activation: + controller: "MpcController" + + transform_manager: + + open_vins: + odom_topic: "odom" # name of the topic (expects nav_msgs/Odometry topic type) + tf_from_attitude: # used for transforming velocities before full transform is available + enabled: true + attitude_topic: "attitude" # name of the attitude topic(expects geometry_msgs/QuaternionStamped topic type) + namespace: "estimation_manager/open_vins" # the namespace of the topic (usually the node that publishes the topic) + utm_based: false # if true, will publish tf to utm_origin + inverted: true # publish as inverted tf (the default for inverted mrs tf tree convention) + republish_in_frames: [] # the odometry message will be transformed and republished in the specified frames + +mrs_uav_trackers: + + landoff_tracker: + + max_position_difference: 2.0 + vertical_tracker: + + takeoff_speed: 1.0 + takeoff_acceleration: 0.5 + diff --git a/tmux/robofly/config/network_config.yaml b/tmux/robofly/config/network_config.yaml new file mode 100644 index 0000000..08f370d --- /dev/null +++ b/tmux/robofly/config/network_config.yaml @@ -0,0 +1,15 @@ +# 1. This list is used by NimbroNetwork for mutual communication of the UAVs +# The names of the robots have to match hostnames described in /etc/hosts. +# +# 2. This list is used by MpcTracker for mutual collision avoidance of the UAVs. +# The names should match the true "UAV_NAMES" (the topic prefixes). +# +# network_config:=~/config/network_config.yaml +# +# to the core.launch and nimbro.launch. + +network: + + robot_names: [ + uav1, + ] diff --git a/tmux/robofly/record.sh b/tmux/robofly/record.sh new file mode 100755 index 0000000..b5043ba --- /dev/null +++ b/tmux/robofly/record.sh @@ -0,0 +1,65 @@ +#!/bin/bash + +path="/home/\$(optenv USER mrs)/bag_files/latest/" + +# By default, we record everything. +# Except for this list of EXCLUDED topics: +exclude=( + +# IN GENERAL, DON'T RECORD CAMERAS +# +# If you want to record cameras, create a copy of this script +# and place it at your tmux session. +# +# Please, seek an advice of a senior researcher of MRS about +# what can be recorded. Recording too much data can lead to +# ROS communication hiccups, which can lead to eland, failsafe +# or just a CRASH. + +# Every topic containing "compressed" +# '(.*)compressed(.*)' +# Every topic containing "image_raw" +# '(.*)image_raw(.*)' +# Every topic containing "theora" +# '(.*)theora(.*)' +# Every topic containing "h264" +# '(.*)h264(.*)' + +) + +# file's header +filename=`mktemp` +echo "" > "$filename" +echo "" >> "$filename" +echo "" >> "$filename" + +echo -n "> "$filename" + +# if there is anything to exclude +if [ "${#exclude[*]}" -gt 0 ]; then + + echo -n " -x " >> "$filename" + + # list all the string and separate the with | + for ((i=0; i < ${#exclude[*]}; i++)); + do + echo -n "${exclude[$i]}" >> "$filename" + if [ "$i" -lt "$( expr ${#exclude[*]} - 1)" ]; then + echo -n "|" >> "$filename" + fi + done + +fi + +echo "\">" >> "$filename" + +echo "" >> "$filename" +echo "" >> "$filename" + +# file's footer +echo "" >> "$filename" +echo "" >> "$filename" +echo "" >> "$filename" + +cat $filename +roslaunch $filename diff --git a/tmux/robofly/tmux.sh b/tmux/robofly/tmux.sh new file mode 100755 index 0000000..f4038d1 --- /dev/null +++ b/tmux/robofly/tmux.sh @@ -0,0 +1,179 @@ +#!/bin/bash +### BEGIN INIT INFO +# Provides: tmux +# Required-Start: $local_fs $network dbus +# Required-Stop: $local_fs $network +# Default-Start: 2 3 4 5 +# Default-Stop: 0 1 6 +# Short-Description: start the uav +### END INIT INFO +if [ "$(id -u)" == "0" ]; then + exec sudo -u mrs "$0" "$@" +fi + +source $HOME/.bashrc + +# location for storing the bag files +# * do not change unless you know what you are doing +MAIN_DIR=~/"bag_files" + +# the project name +# * is used to define folder name in ~/$MAIN_DIR +PROJECT_NAME=just_flying + +# the name of the TMUX session +# * can be used for attaching as 'tmux a -t ' +SESSION_NAME=mav + +# following commands will be executed first in each window +# * do NOT put ; at the end +pre_input="" + +# define commands +# 'name' 'command' +# * DO NOT PUT SPACES IN THE NAMES +# * "new line" after the command => the command will be called after start +# * NO "new line" after the command => the command will wait for user's +input=( + 'Rosbag' 'waitForTime; ./record.sh' + 'Sensors' 'waitForTime; roslaunch mrs_uav_deployment sensors.launch +' + 'HwApi' 'waitForTime; roslaunch mrs_uav_px4_api api.launch +' + 'Status' 'waitForHw; roslaunch mrs_uav_status status.launch +' + 'midair' 'rosservice call /'"$UAV_NAME"'/uav_manager/midair_activation' + 'OpenVins' 'waitForHw; roslaunch mrs_open_vins_core robofly.launch +' + 'VinsRepublisher' 'waitForHw; roslaunch mrs_vins_republisher vins_republisher_openvins_unreal.launch +' + 'Camera' 'waitForTime; roslaunch libcamera_ros uav.launch +' + 'IMU' 'waitForTime; roslaunch mrs_icm_imu_driver imu.launch +' + 'Autostart' 'waitForHw; roslaunch mrs_uav_autostart automatic_start.launch +' + 'Core' 'waitForTime; roslaunch mrs_uav_core core.launch platform_config:=`rospack find mrs_uav_deployment`/config/mrs_uav_system/$UAV_TYPE.yaml world_config:=`rospack find mrs_uav_deployment`/config/worlds/world_$WORLD_NAME.yaml custom_config:=./config/custom_config.yaml network_config:=./config/network_config.yaml +' + # 'AutoStart' 'waitForHw; roslaunch mrs_uav_autostart automatic_start.launch +# ' +# do NOT modify the command list below + 'EstimDiag' 'waitForHw; rostopic echo /'"$UAV_NAME"'/estimation_manager/diagnostics +' + 'kernel_log' 'tail -f /var/log/kern.log -n 100 +' + 'roscore' 'roscore +' + 'simtime' 'waitForRos; rosparam set use_sim_time false +' +) + +# the name of the window to focus after start +init_window="Status" + +# automatically attach to the new session? +# {true, false}, default true +attach=true + +########################### +### DO NOT MODIFY BELOW ### +########################### + +export TMUX_BIN="/usr/bin/tmux -L mrs -f /etc/ctu-mrs/tmux.conf" + +# find the session +FOUND=$( $TMUX_BIN ls | grep $SESSION_NAME ) + +if [ $? == "0" ]; then + echo "The session already exists" + $TMUX_BIN -2 attach-session -t $SESSION_NAME + exit +fi + +# Absolute path to this script. /home/user/bin/foo.sh +SCRIPT=$(readlink -f $0) +# Absolute path this script is in. /home/user/bin +SCRIPTPATH=`dirname $SCRIPT` + +TMUX= $TMUX_BIN new-session -s "$SESSION_NAME" -d +echo "Starting new session." + +# get the iterator +ITERATOR_FILE="$MAIN_DIR/$PROJECT_NAME"/iterator.txt +if [ -e "$ITERATOR_FILE" ] +then + ITERATOR=`cat "$ITERATOR_FILE"` + ITERATOR=$(($ITERATOR+1)) +else + echo "iterator.txt does not exist, creating it" + mkdir -p "$MAIN_DIR/$PROJECT_NAME" + touch "$ITERATOR_FILE" + ITERATOR="1" +fi +echo "$ITERATOR" > "$ITERATOR_FILE" + +# create file for logging terminals' output +LOG_DIR="$MAIN_DIR/$PROJECT_NAME/" +SUFFIX=$(date +"%Y_%m_%d_%H_%M_%S") +SUBLOG_DIR="$LOG_DIR/"$ITERATOR"_"$SUFFIX"" +TMUX_DIR="$SUBLOG_DIR/tmux" +mkdir -p "$SUBLOG_DIR" +mkdir -p "$TMUX_DIR" + +# link the "latest" folder to the recently created one +rm "$LOG_DIR/latest" > /dev/null 2>&1 +rm "$MAIN_DIR/latest" > /dev/null 2>&1 +ln -sf "$SUBLOG_DIR" "$LOG_DIR/latest" +ln -sf "$SUBLOG_DIR" "$MAIN_DIR/latest" + +# create arrays of names and commands +for ((i=0; i < ${#input[*]}; i++)); +do + ((i%2==0)) && names[$i/2]="${input[$i]}" + ((i%2==1)) && cmds[$i/2]="${input[$i]}" +done + +# run tmux windows +for ((i=0; i < ${#names[*]}; i++)); +do + $TMUX_BIN new-window -t $SESSION_NAME:$(($i+1)) -n "${names[$i]}" +done + +sleep 3 + +# start loggers +for ((i=0; i < ${#names[*]}; i++)); +do + $TMUX_BIN pipe-pane -t $SESSION_NAME:$(($i+1)) -o "ts | cat >> $TMUX_DIR/$(($i+1))_${names[$i]}.log" +done + +# send commands +for ((i=0; i < ${#cmds[*]}; i++)); +do + $TMUX_BIN send-keys -t $SESSION_NAME:$(($i+1)) "cd $SCRIPTPATH; ${pre_input}; ${cmds[$i]}" +done + +# identify the index of the init window +init_index=0 +for ((i=0; i < ((${#names[*]})); i++)); +do + if [ ${names[$i]} == "$init_window" ]; then + init_index=$(expr $i + 1) + fi +done + +$TMUX_BIN select-window -t $SESSION_NAME:$init_index + +if $attach; then + + if [ -z ${TMUX} ]; + then + $TMUX_BIN -2 attach-session -t $SESSION_NAME + else + tmux detach-client -E "tmux -L mrs a -t $SESSION_NAME" + fi +else + echo "The session was started" + echo "You can later attach by calling:" + echo " tmux -L mrs a -t $SESSION_NAME" +fi