diff --git a/launch/rpa_positioning.launch b/launch/rpa_positioning.launch index f7035a6dc77b96c9d13c17913dbb3730a5920dba..bd45cc5fece52991c0d6ae075a773c237c3e34a1 100644 --- a/launch/rpa_positioning.launch +++ b/launch/rpa_positioning.launch @@ -4,6 +4,7 @@ <arg name="platform" default="M600" /> <arg name="only_gnss" default="false" /> + <arg name="emulate_ublox" default="false" /> <arg name="yaml" default="params" unless="$(arg only_gnss)"/> <arg name="yaml" default="params_only_gnss" if="$(arg only_gnss)"/> @@ -20,7 +21,7 @@ </group> <!-- UBLOX EMULATOR (ONLY FOR TUCAN) --> - <group if="$(eval platform == 'tucan')"> + <group if="$(arg emulate_ublox)"> <node name="ublox_emulator" pkg ="iri_ublox_emulator" type="iri_ublox_emulator" diff --git a/launch/rpa_positioning_rosbag_second_field.launch b/launch/rpa_positioning_rosbag_second_field.launch index dec8aa106f23b5aa2a756b0ffedde8eb3bf040f4..ca3f25e3041425de40c4c15a7e1d002ddcd34f39 100644 --- a/launch/rpa_positioning_rosbag_second_field.launch +++ b/launch/rpa_positioning_rosbag_second_field.launch @@ -29,11 +29,23 @@ <arg name="bag_suffix" value="M600b_2021-09-17-11-00-51" if="$(eval flight == 'M600b_17_1')" /> <arg name="bag_suffix" value="M600b_2021-09-17-11-31-55" if="$(eval flight == 'M600b_17_2')" /> <arg name="bag_suffix" value="scrab_2021-09-16-11-25-23" if="$(eval flight == 'scrab_16')" /> - <arg name="bag_suffix" value="scrab_2021-09-17-09-59-32" if="$(eval flight == 'scrab_17')" /> - - <arg name="platform" value="atlantic" if="$(eval flight == 'atlantic_16' or flight == 'atlantic_17')" /> - <arg name="platform" value="M600b" if="$(eval flight == 'M600b_16_1' or flight == 'M600b_16_2' or flight == 'M600b_17_1' or flight == 'M600b_17_2')" /> + <arg name="bag_suffix" value="scrab_2021-09-17-09-59-32" if="$(eval flight == 'scrab_16')" /> + + <arg name="bag_suffix" value="atlantic_2021-05-28-08-11-00" if="$(eval flight == 'atlantic_28')" /> + <arg name="bag_suffix" value="M600a_2021-05-27-11-24-42" if="$(eval flight == 'M600a_27_1')" /> + <arg name="bag_suffix" value="M600a_2021-05-27-11-55-45" if="$(eval flight == 'M600a_27_2')" /> + <arg name="bag_suffix" value="M600a_2021-05-27-13-17-29" if="$(eval flight == 'M600a_27_3')" /> + <arg name="bag_suffix" value="M600a_2021-05-28-08-24-11" if="$(eval flight == 'M600a_28_1')" /> + <arg name="bag_suffix" value="M600a_2021-05-28-08-50-42" if="$(eval flight == 'M600a_28_2')" /> + <arg name="bag_suffix" value="M600b_2021-05-27-14-39-11" if="$(eval flight == 'M600b_27')" /> + <arg name="bag_suffix" value="M600b_2021-05-28-09-57-29" if="$(eval flight == 'M600b_28')" /> + <arg name="bag_suffix" value="tucan_2021-05-28-11-00-22" if="$(eval flight == 'tucan')" /> + + <arg name="platform" value="atlantic" if="$(eval flight == 'atlantic_16' or flight == 'atlantic_17' or flight == 'atlantic_28')" /> + <arg name="platform" value="M600b" if="$(eval flight == 'M600b_16_1' or flight == 'M600b_16_2' or flight == 'M600b_17_1' or flight == 'M600b_17_2' or flight == 'M600b_27' or flight == 'M600b_28')" /> <arg name="platform" value="scrab" if="$(eval flight == 'scrab_16' or flight == 'scrab_17')" /> + <arg name="platform" value="tucan" if="$(eval flight == 'tucan')" /> + <arg name="platform" value="M600a" if="$(eval flight == 'M600a_27_1' or flight == 'M600a_27_2' or flight == 'M600a_27_3' or flight == 'M600a_28_1' or flight == 'M600a_28_2')" /> <arg name="sec" default="5500" if="$(eval flight == 'atlantic_16')" /> <arg name="sec" default="0" if="$(eval flight == 'atlantic_17')" /> @@ -43,6 +55,15 @@ <arg name="sec" default="0" if="$(eval flight == 'M600b_17_2')" /> <arg name="sec" default="0" if="$(eval flight == 'scrab_16')" /> <arg name="sec" default="0" if="$(eval flight == 'scrab_17')" /> + <arg name="sec" default="0" if="$(eval flight == 'atlantic_28')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600a_27_1')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600a_27_2')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600a_27_3')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600a_28_1')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600a_28_2')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600b_27')" /> + <arg name="sec" default="0" if="$(eval flight == 'M600b_28')" /> + <arg name="sec" default="0" if="$(eval flight == 'tucan')" /> <arg name="yaml" value="params" if="$(eval conf_gnss == 1)" /> <arg name="yaml" value="params_2" if="$(eval conf_gnss == 2)" /> diff --git a/launch/rpa_positioning_sensors.launch b/launch/rpa_positioning_sensors.launch index 0ed47b44117e5b74ea250f928fc2486f7da1d1b6..6b9b84d740ed362a6bc0d62d752d81d0ed1a20b0 100644 --- a/launch/rpa_positioning_sensors.launch +++ b/launch/rpa_positioning_sensors.launch @@ -30,6 +30,7 @@ <arg name="mqtt" value="$(arg mqtt)"/> <arg name="remote_server" value="$(arg remote_server)"/> <arg name="output" value="$(arg output)"/> + <arg name="emulate_ublox" value="$(eval platform == 'tucan')"/> </include> <!--SENSORS--> diff --git a/scripts/multi_launch_positioning_rosbag_ATLAS.sh b/scripts/multi_launch_positioning_rosbag_ATLAS.sh new file mode 100755 index 0000000000000000000000000000000000000000..744cf271d3f58fdee83ef4526d93debb88c329eb --- /dev/null +++ b/scripts/multi_launch_positioning_rosbag_ATLAS.sh @@ -0,0 +1,15 @@ +#!/bin/bash + +EXPERIMENTS=('atlantic_28' 'M600a_27_1' 'M600a_27_2' 'M600a_27_3' 'M600a_28_1' 'M600a_28_2' 'M600b_27' 'M600b_28' 'tucan') +CONFIGS=(1 2 3 4) +BAG_PATH="/media/jvallve/DADES/bags/GAUSS/second_field_trials_ATLAS/selected" + +for experiment in "${EXPERIMENTS[@]}" +do + for config in "${CONFIGS[@]}" + do + logfile="${BAG_PATH}/roslog_${experiment}_config${config}.txt" + echo "Launch rpa_positioning_rosbag_second_field.launch with $experiment in mode $config ang generating log $logfile..." + roslaunch gauss_ros rpa_positioning_rosbag_second_field.launch flight:=$experiment conf_gnss:=$config rviz:=true bag_path:=$BAG_PATH > $logfile + done +done \ No newline at end of file diff --git a/yaml/M600a/params.yaml b/yaml/M600a/params.yaml index a22422a23dc83922092e2cc0fe1c889ce3144eb0..d75a0a8a21aa975870f13f737f56223a185f6ea4 100644 --- a/yaml/M600a/params.yaml +++ b/yaml/M600a/params.yaml @@ -50,6 +50,10 @@ config: extrinsic: pose: [0.0, 0.0, 0.28] # M600 follow: "../sensor_f9t.yaml" + - + type: "SensorModel" + name: "dynamic_model" + plugin: "core" processors: - @@ -70,6 +74,12 @@ config: sensor_name: "gnss" plugin: "gnss" follow: "processor_gnss.yaml" + - + type: "ProcessorFixWingModel" + name: "processor fix wing" + sensor_name: "dynamic_model" + plugin: "core" + follow: "processor_fix_wing.yaml" ROS subscriber: - diff --git a/yaml/M600a/params_2.yaml b/yaml/M600a/params_2.yaml new file mode 100644 index 0000000000000000000000000000000000000000..07916e0877667cfaf2b2ba0f4609d4055f467b48 --- /dev/null +++ b/yaml/M600a/params_2.yaml @@ -0,0 +1,169 @@ +config: + debug: + profiling: true + profiling_file: "~/profiling_M600b.txt" + print_problem: false + print_period: 1 + print_depth: 4 + print_constr_by: false + print_metric: true + print_state_blocks: false + + problem: + frame_structure: "POV" + dimension: 3 + tree_manager: + follow: "../tree_manager/sliding_window_20_0.yaml" + prior: + follow: "../prior/POV_fix.yaml" + + solver: + max_num_iterations: 20 + verbose: 0 + period: 0.0 + n_threads: 2 + update_immediately: false + min_num_iterations: 5 #if update immediately + compute_cov: true + cov_enum: 3 + cov_period: 1 + + map: + type: "MapBase" + plugin: "core" + + sensors: + - + type: "SensorImu" + name: "IMU_odometer" + plugin: "imu" + follow: "../sensor_bno.yaml" + #- + # type: "SensorCompass" + # name: "compass" + # plugin: "imu" + # follow: "sensor_bno_compass.yaml" + - + type: "SensorGnss" + name: "gnss" + plugin: "gnss" + extrinsic: + pose: [0.0, 0.0, 0.28] # M600 + follow: "../sensor_f9t.yaml" + - + type: "SensorModel" + name: "dynamic_model" + plugin: "core" + + processors: + - + type: "ProcessorImu" + name: "processor IMU" + sensor_name: "IMU_odometer" + plugin: "imu" + follow: "../processor_imu.yaml" + #- + # type: "ProcessorCompass" + # name: "processor compass" + # sensor_name: "compass" + # plugin: "imu" + # follow: "../processor_compass.yaml" + - + type: "ProcessorTrackerGnss" + name: "processor gnss" + sensor_name: "gnss" + plugin: "gnss" + follow: "processor_gnss_2.yaml" + - + type: "ProcessorFixWingModel" + name: "processor fix wing" + sensor_name: "dynamic_model" + plugin: "core" + follow: "processor_fix_wing.yaml" + + ROS subscriber: + - + type: "SubscriberGnssUblox" + topic: "/ublox_gps/raw_data_stream" + sensor_name: "gnss" + package: "wolf_ros_gnss" + follow: "../subscriber_gnss_ublox_2.yaml" + - + type: "SubscriberImuEnableable" + topic: "/bno055_imu/imu" + sensor_name: "IMU_odometer" + package: "wolf_ros_imu" + follow: "subscriber_imu.yaml" + #- + # type: "SubscriberCompass" + # topic: "/bno055_imu/magnetometer" + # sensor_name: "compass" + # package: "wolf_ros_imu" + # follow: "subscriber_imu.yaml" + - + type: "SubscriberGnssFixPublisherEcef" + topic: "/ublox_gps/fix" + sensor_name: "gnss" + package: "wolf_ros_gnss" + marker_color: [0,0,1,1] + line_size: 0.2 + period: 0.2 + max_points: 10000 + + ROS publisher: + - + type: "PublisherRpaStateInfo" + topic: "rpa_state_info" + package: "wolf_ros_gauss" + period: 0.5 + follow: "publisher_rpa_state_info.yaml" + - + type: "PublisherRpaPositioningInfo" + topic: "rpa_positioning_info" + package: "wolf_ros_gauss" + period: 0.5 + sensor: "gnss" + - + type: "PublisherRpaImuGnssPositioning" + topic: "rpa_imu_gnss_positioning" + package: "wolf_ros_gauss" + period: 0.1 + sensor: "gnss" + - + type: "PublisherPose" + topic: "current_pose" + package: "wolf_ros_node" + marker_color: [1,0,0,1] + line_size: 0.2 + period: 0.2 + extrinsics: true + sensor: "gnss" + frame_id: "ENU" + max_points: 10000 + - + type: "PublisherGnssTf" + topic: " " + package: "wolf_ros_gnss" + period: 0.01 + sensor_gnss_name: "gnss" + - + type: "PublisherTf" + topic: " " + package: "wolf_ros_node" + period: 0.2 + map_frame_id: "map" + odom_frame_id: "odom" + base_frame_id: "base" + publish_odom_tf: false + - + type: "PublisherGraph" + topic: "graph" + package: "wolf_ros_node" + period: 0.2 + viz_scale: 2 + - + type: "PublisherTrackerGnssInfo" + topic: "gnss_tracker" + package: "wolf_ros_gnss" + period: 0.2 + processor_gnss: "processor gnss" \ No newline at end of file diff --git a/yaml/M600a/params_3.yaml b/yaml/M600a/params_3.yaml new file mode 100644 index 0000000000000000000000000000000000000000..d09eeada3b47e206dfa7f1fd8195cd4e61007b63 --- /dev/null +++ b/yaml/M600a/params_3.yaml @@ -0,0 +1,169 @@ +config: + debug: + profiling: true + profiling_file: "~/profiling_M600b.txt" + print_problem: false + print_period: 1 + print_depth: 4 + print_constr_by: false + print_metric: true + print_state_blocks: false + + problem: + frame_structure: "POV" + dimension: 3 + tree_manager: + follow: "../tree_manager/sliding_window_20_0.yaml" + prior: + follow: "../prior/POV_fix.yaml" + + solver: + max_num_iterations: 20 + verbose: 0 + period: 0.0 + n_threads: 2 + update_immediately: false + min_num_iterations: 5 #if update immediately + compute_cov: true + cov_enum: 3 + cov_period: 1 + + map: + type: "MapBase" + plugin: "core" + + sensors: + - + type: "SensorImu" + name: "IMU_odometer" + plugin: "imu" + follow: "../sensor_bno.yaml" + #- + # type: "SensorCompass" + # name: "compass" + # plugin: "imu" + # follow: "sensor_bno_compass.yaml" + - + type: "SensorGnss" + name: "gnss" + plugin: "gnss" + extrinsic: + pose: [0.0, 0.0, 0.28] # M600 + follow: "../sensor_f9t.yaml" + - + type: "SensorModel" + name: "dynamic_model" + plugin: "core" + + processors: + - + type: "ProcessorImu" + name: "processor IMU" + sensor_name: "IMU_odometer" + plugin: "imu" + follow: "../processor_imu.yaml" + #- + # type: "ProcessorCompass" + # name: "processor compass" + # sensor_name: "compass" + # plugin: "imu" + # follow: "../processor_compass.yaml" + - + type: "ProcessorTrackerGnss" + name: "processor gnss" + sensor_name: "gnss" + plugin: "gnss" + follow: "processor_gnss_3.yaml" + - + type: "ProcessorFixWingModel" + name: "processor fix wing" + sensor_name: "dynamic_model" + plugin: "core" + follow: "processor_fix_wing.yaml" + + ROS subscriber: + - + type: "SubscriberGnssUblox" + topic: "/ublox_gps/raw_data_stream" + sensor_name: "gnss" + package: "wolf_ros_gnss" + follow: "../subscriber_gnss_ublox_3.yaml" + - + type: "SubscriberImuEnableable" + topic: "/bno055_imu/imu" + sensor_name: "IMU_odometer" + package: "wolf_ros_imu" + follow: "subscriber_imu.yaml" + #- + # type: "SubscriberCompass" + # topic: "/bno055_imu/magnetometer" + # sensor_name: "compass" + # package: "wolf_ros_imu" + # follow: "subscriber_imu.yaml" + - + type: "SubscriberGnssFixPublisherEcef" + topic: "/ublox_gps/fix" + sensor_name: "gnss" + package: "wolf_ros_gnss" + marker_color: [0,0,1,1] + line_size: 0.2 + period: 0.2 + max_points: 10000 + + ROS publisher: + - + type: "PublisherRpaStateInfo" + topic: "rpa_state_info" + package: "wolf_ros_gauss" + period: 0.5 + follow: "publisher_rpa_state_info.yaml" + - + type: "PublisherRpaPositioningInfo" + topic: "rpa_positioning_info" + package: "wolf_ros_gauss" + period: 0.5 + sensor: "gnss" + - + type: "PublisherRpaImuGnssPositioning" + topic: "rpa_imu_gnss_positioning" + package: "wolf_ros_gauss" + period: 0.1 + sensor: "gnss" + - + type: "PublisherPose" + topic: "current_pose" + package: "wolf_ros_node" + marker_color: [1,0,0,1] + line_size: 0.2 + period: 0.2 + extrinsics: true + sensor: "gnss" + frame_id: "ENU" + max_points: 10000 + - + type: "PublisherGnssTf" + topic: " " + package: "wolf_ros_gnss" + period: 0.01 + sensor_gnss_name: "gnss" + - + type: "PublisherTf" + topic: " " + package: "wolf_ros_node" + period: 0.2 + map_frame_id: "map" + odom_frame_id: "odom" + base_frame_id: "base" + publish_odom_tf: false + - + type: "PublisherGraph" + topic: "graph" + package: "wolf_ros_node" + period: 0.2 + viz_scale: 2 + - + type: "PublisherTrackerGnssInfo" + topic: "gnss_tracker" + package: "wolf_ros_gnss" + period: 0.2 + processor_gnss: "processor gnss" \ No newline at end of file diff --git a/yaml/M600a/params_4.yaml b/yaml/M600a/params_4.yaml new file mode 100644 index 0000000000000000000000000000000000000000..14a02dead496abee1e06aadba4a986e635bcdba1 --- /dev/null +++ b/yaml/M600a/params_4.yaml @@ -0,0 +1,169 @@ +config: + debug: + profiling: true + profiling_file: "~/profiling_M600b.txt" + print_problem: false + print_period: 1 + print_depth: 4 + print_constr_by: false + print_metric: true + print_state_blocks: false + + problem: + frame_structure: "POV" + dimension: 3 + tree_manager: + follow: "../tree_manager/sliding_window_20_0.yaml" + prior: + follow: "../prior/POV_fix.yaml" + + solver: + max_num_iterations: 20 + verbose: 0 + period: 0.0 + n_threads: 2 + update_immediately: false + min_num_iterations: 5 #if update immediately + compute_cov: true + cov_enum: 3 + cov_period: 1 + + map: + type: "MapBase" + plugin: "core" + + sensors: + - + type: "SensorImu" + name: "IMU_odometer" + plugin: "imu" + follow: "../sensor_bno.yaml" + #- + # type: "SensorCompass" + # name: "compass" + # plugin: "imu" + # follow: "sensor_bno_compass.yaml" + - + type: "SensorGnss" + name: "gnss" + plugin: "gnss" + extrinsic: + pose: [0.0, 0.0, 0.28] # M600 + follow: "../sensor_f9t.yaml" + - + type: "SensorModel" + name: "dynamic_model" + plugin: "core" + + processors: + - + type: "ProcessorImu" + name: "processor IMU" + sensor_name: "IMU_odometer" + plugin: "imu" + follow: "../processor_imu.yaml" + #- + # type: "ProcessorCompass" + # name: "processor compass" + # sensor_name: "compass" + # plugin: "imu" + # follow: "../processor_compass.yaml" + - + type: "ProcessorTrackerGnss" + name: "processor gnss" + sensor_name: "gnss" + plugin: "gnss" + follow: "processor_gnss_4.yaml" + - + type: "ProcessorFixWingModel" + name: "processor fix wing" + sensor_name: "dynamic_model" + plugin: "core" + follow: "processor_fix_wing.yaml" + + ROS subscriber: + - + type: "SubscriberGnssUblox" + topic: "/ublox_gps/raw_data_stream" + sensor_name: "gnss" + package: "wolf_ros_gnss" + follow: "../subscriber_gnss_ublox_4.yaml" + - + type: "SubscriberImuEnableable" + topic: "/bno055_imu/imu" + sensor_name: "IMU_odometer" + package: "wolf_ros_imu" + follow: "subscriber_imu.yaml" + #- + # type: "SubscriberCompass" + # topic: "/bno055_imu/magnetometer" + # sensor_name: "compass" + # package: "wolf_ros_imu" + # follow: "subscriber_imu.yaml" + - + type: "SubscriberGnssFixPublisherEcef" + topic: "/ublox_gps/fix" + sensor_name: "gnss" + package: "wolf_ros_gnss" + marker_color: [0,0,1,1] + line_size: 0.2 + period: 0.2 + max_points: 10000 + + ROS publisher: + - + type: "PublisherRpaStateInfo" + topic: "rpa_state_info" + package: "wolf_ros_gauss" + period: 0.5 + follow: "publisher_rpa_state_info.yaml" + - + type: "PublisherRpaPositioningInfo" + topic: "rpa_positioning_info" + package: "wolf_ros_gauss" + period: 0.5 + sensor: "gnss" + - + type: "PublisherRpaImuGnssPositioning" + topic: "rpa_imu_gnss_positioning" + package: "wolf_ros_gauss" + period: 0.1 + sensor: "gnss" + - + type: "PublisherPose" + topic: "current_pose" + package: "wolf_ros_node" + marker_color: [1,0,0,1] + line_size: 0.2 + period: 0.2 + extrinsics: true + sensor: "gnss" + frame_id: "ENU" + max_points: 10000 + - + type: "PublisherGnssTf" + topic: " " + package: "wolf_ros_gnss" + period: 0.01 + sensor_gnss_name: "gnss" + - + type: "PublisherTf" + topic: " " + package: "wolf_ros_node" + period: 0.2 + map_frame_id: "map" + odom_frame_id: "odom" + base_frame_id: "base" + publish_odom_tf: false + - + type: "PublisherGraph" + topic: "graph" + package: "wolf_ros_node" + period: 0.2 + viz_scale: 2 + - + type: "PublisherTrackerGnssInfo" + topic: "gnss_tracker" + package: "wolf_ros_gnss" + period: 0.2 + processor_gnss: "processor gnss" \ No newline at end of file diff --git a/yaml/M600a/processor_fix_wing.yaml b/yaml/M600a/processor_fix_wing.yaml new file mode 100644 index 0000000000000000000000000000000000000000..115b1eaf1f96ae970b31d9d658f62dac4bc8ef5c --- /dev/null +++ b/yaml/M600a/processor_fix_wing.yaml @@ -0,0 +1,7 @@ +time_tolerance: 0.005 # Time tolerance for joining KFs +keyframe_vote: + voting_active: false +apply_loss_function: false +velocity_local: [1, 0, 0] +angle_stdev: 0.05 +min_vel_norm: 1 \ No newline at end of file diff --git a/yaml/M600a/processor_gnss_2.yaml b/yaml/M600a/processor_gnss_2.yaml new file mode 100644 index 0000000000000000000000000000000000000000..0af73990647fbfdbcc5d9239ea7b20f7a3f13fe7 --- /dev/null +++ b/yaml/M600a/processor_gnss_2.yaml @@ -0,0 +1,45 @@ +time_tolerance: 0.1 +apply_loss_function: false +max_new_features: -1 #unlimited +remove_outliers: true +remove_outliers_with_fix: true +outlier_residual_th: 10 +init_frames: false +pseudo_ranges: true +fix: false +enu_map_fix_dist: 5 +keyframe_vote: + voting_active: true + max_time_span: 0.5 + min_features_for_keyframe: 0 #4 +gnss: + sateph: 0 # satellite ephemeris/clock: EPHOPT_BRDC(0):broadcast ephemeris, EPHOPT_PREC(1): precise ephemeris, EPHOPT_SBAS(2): broadcast + SBAS, EPHOPT_SSRAPC(3): broadcast + SSR_APC, EPHOPT_SSRCOM(4): broadcast + SSR_COM, EPHOPT_LEX(5): QZSS LEX ephemeris, EPHOPT_SBAS2(6):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), EPHOPT_SBAS3(7):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_SBAS2), EPHOPT_SBAS4(8):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_BRDC) + ionoopt: 1 # ionosphere option: IONOOPT_OFF(0):correction off, IONOOPT_BRDC(1):broadcast mode, IONOOPT_SBAS(2):SBAS model, IONOOPT_IFLC(3):L1/L2 or L1/L5, IONOOPT_EST(4):estimation, IONOOPT_TEC(5):IONEX TEC model, IONOOPT_QZS(6):QZSS broadcast, IONOOPT_LEX(7):QZSS LEX ionosphere, IONOOPT_STEC(8):SLANT TEC mode, IONOOPT_SBAS2(9):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), IONOOPT_SBAS3(10):broadcast + SBAS(IONOOPT_SBAS if possible, otherwise IONOOPT_SBAS2), IONOOPT_SBAS4(8):broadcast + SBAS(IONOOPT_SBAS if possible, otherwise IONOOPT_BRDC) + tropopt: 1 # troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) + sbascorr: 15 # SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) + raim: 1 # apply RAIM + elmin: 0.26 # elevation min (rad) = 15 degrees + maxgdop: 30 # reject threshold of gdop (ground dilusion of precision) + min_sbas_sats: 5 # used in case of EPHOPT_SBAS3, EPHOPT_SBAS4, IONOOPT_SBAS3, IONOOPT_SBAS4 + constellations: + GPS: true + SBS: false + GLO: false + GAL: true + QZS: false + CMP: false + IRN: false + LEO: false + tdcp: + enabled: true + structure: consecutive + corr_iono: true + corr_tropo: true + corr_clock: true + loss_function: false + time_window: 10 # s + sigma_atm: 0.0016 #1.6mm/sqrt(s) # m/sqrt(s) + sigma_carrier: 0.0011 #1.1mm/sqrt(s) # m + multi_freq: false + remove_outliers: false + batch: false \ No newline at end of file diff --git a/yaml/M600a/processor_gnss_3.yaml b/yaml/M600a/processor_gnss_3.yaml new file mode 100644 index 0000000000000000000000000000000000000000..0483aece09c007f8c00054a87ac1fa3cf658ebc4 --- /dev/null +++ b/yaml/M600a/processor_gnss_3.yaml @@ -0,0 +1,45 @@ +time_tolerance: 0.1 +apply_loss_function: false +max_new_features: -1 #unlimited +remove_outliers: true +remove_outliers_with_fix: true +outlier_residual_th: 10 +init_frames: false +pseudo_ranges: true +fix: false +enu_map_fix_dist: 5 +keyframe_vote: + voting_active: true + max_time_span: 0.5 + min_features_for_keyframe: 0 #4 +gnss: + sateph: 6 # satellite ephemeris/clock: EPHOPT_BRDC(0):broadcast ephemeris, EPHOPT_PREC(1): precise ephemeris, EPHOPT_SBAS(2): broadcast + SBAS, EPHOPT_SSRAPC(3): broadcast + SSR_APC, EPHOPT_SSRCOM(4): broadcast + SSR_COM, EPHOPT_LEX(5): QZSS LEX ephemeris, EPHOPT_SBAS2(6):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), EPHOPT_SBAS3(7):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_SBAS2), EPHOPT_SBAS4(8):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_BRDC) + ionoopt: 9 # ionosphere option: IONOOPT_OFF(0):correction off, IONOOPT_BRDC(1):broadcast mode, IONOOPT_SBAS(2):SBAS model, IONOOPT_IFLC(3):L1/L2 or L1/L5, IONOOPT_EST(4):estimation, IONOOPT_TEC(5):IONEX TEC model, IONOOPT_QZS(6):QZSS broadcast, IONOOPT_LEX(7):QZSS LEX ionosphere, IONOOPT_STEC(8):SLANT TEC mode, IONOOPT_SBAS2(9):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), IONOOPT_SBAS3(10):broadcast + SBAS(IONOOPT_SBAS if possible, otherwise IONOOPT_SBAS2), IONOOPT_SBAS4(8):broadcast + SBAS(IONOOPT_SBAS if possible, otherwise IONOOPT_BRDC) + tropopt: 2 # troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) + sbascorr: 15 # SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) + raim: 1 # apply RAIM + elmin: 0.26 # elevation min (rad) = 15 degrees + maxgdop: 30 # reject threshold of gdop (ground dilusion of precision) + min_sbas_sats: 5 # used in case of EPHOPT_SBAS3, EPHOPT_SBAS4, IONOOPT_SBAS3, IONOOPT_SBAS4 + constellations: + GPS: true + SBS: false + GLO: false + GAL: false + QZS: false + CMP: false + IRN: false + LEO: false + tdcp: + enabled: true + structure: consecutive + corr_iono: true + corr_tropo: true + corr_clock: true + loss_function: false + time_window: 10 # s + sigma_atm: 0.0016 #1.6mm/sqrt(s) # m/sqrt(s) + sigma_carrier: 0.0011 #1.1mm/sqrt(s) # m + multi_freq: false + remove_outliers: false + batch: false \ No newline at end of file diff --git a/yaml/M600a/processor_gnss_4.yaml b/yaml/M600a/processor_gnss_4.yaml new file mode 100644 index 0000000000000000000000000000000000000000..25c554acbc4d6c7f11caaedaa26a639e3dbf58a7 --- /dev/null +++ b/yaml/M600a/processor_gnss_4.yaml @@ -0,0 +1,45 @@ +time_tolerance: 0.1 +apply_loss_function: false +max_new_features: -1 #unlimited +remove_outliers: true +remove_outliers_with_fix: true +outlier_residual_th: 10 +init_frames: false +pseudo_ranges: true +fix: false +enu_map_fix_dist: 5 +keyframe_vote: + voting_active: true + max_time_span: 0.5 + min_features_for_keyframe: 0 #4 +gnss: + sateph: 0 # satellite ephemeris/clock: EPHOPT_BRDC(0):broadcast ephemeris, EPHOPT_PREC(1): precise ephemeris, EPHOPT_SBAS(2): broadcast + SBAS, EPHOPT_SSRAPC(3): broadcast + SSR_APC, EPHOPT_SSRCOM(4): broadcast + SSR_COM, EPHOPT_LEX(5): QZSS LEX ephemeris, EPHOPT_SBAS2(6):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), EPHOPT_SBAS3(7):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_SBAS2), EPHOPT_SBAS4(8):broadcast + SBAS(EPHOPT_SBAS if possible, otherwise EPHOPT_BRDC) + ionoopt: 1 # ionosphere option: IONOOPT_OFF(0):correction off, IONOOPT_BRDC(1):broadcast mode, IONOOPT_SBAS(2):SBAS model, IONOOPT_IFLC(3):L1/L2 or L1/L5, IONOOPT_EST(4):estimation, IONOOPT_TEC(5):IONEX TEC model, IONOOPT_QZS(6):QZSS broadcast, IONOOPT_LEX(7):QZSS LEX ionosphere, IONOOPT_STEC(8):SLANT TEC mode, IONOOPT_SBAS2(9):broadcast + SBAS(sats with SBAS corr and sats with BRDC eph), IONOOPT_SBAS3(10):broadcast + SBAS(IONOOPT_SBAS if possible, otherwise IONOOPT_SBAS2), IONOOPT_SBAS4(8):broadcast + SBAS(IONOOPT_SBAS if possible, otherwise IONOOPT_BRDC) + tropopt: 1 # troposphere option: (0:correction off,1:Saastamoinen model,2:SBAS model,3:troposphere option: ZTD estimation,4:ZTD+grad estimation,5:ZTD correction,6:ZTD+grad correction) + sbascorr: 15 # SBAS option (1:long term correction,2:fast correction,4:ionosphere correction,8:ranging) + raim: 1 # apply RAIM + elmin: 0.26 # elevation min (rad) = 15 degrees + maxgdop: 30 # reject threshold of gdop (ground dilusion of precision) + min_sbas_sats: 5 # used in case of EPHOPT_SBAS3, EPHOPT_SBAS4, IONOOPT_SBAS3, IONOOPT_SBAS4 + constellations: + GPS: true + SBS: false + GLO: false + GAL: false + QZS: false + CMP: false + IRN: false + LEO: false + tdcp: + enabled: true + structure: consecutive + corr_iono: true + corr_tropo: true + corr_clock: true + loss_function: false + time_window: 10 # s + sigma_atm: 0.0016 #1.6mm/sqrt(s) # m/sqrt(s) + sigma_carrier: 0.0011 #1.1mm/sqrt(s) # m + multi_freq: false + remove_outliers: false + batch: false \ No newline at end of file diff --git a/yaml/tucan/params.yaml b/yaml/tucan/params.yaml index d8ebca767d99e857fd0619b891618773b8e73be9..ae8771c600869c0b3586a5e0390a5c0fc5cab8b3 100644 --- a/yaml/tucan/params.yaml +++ b/yaml/tucan/params.yaml @@ -38,11 +38,11 @@ config: name: "IMU_odometer" plugin: "imu" follow: "../sensor_bno.yaml" - - - type: "SensorCompass" - name: "compass" - plugin: "imu" - follow: "sensor_bno_compass.yaml" + #- + # type: "SensorCompass" + # name: "compass" + # plugin: "imu" + # follow: "sensor_bno_compass.yaml" - type: "SensorGnss" name: "gnss" @@ -50,6 +50,10 @@ config: extrinsic: pose: [0.30, 0, -0.05] # TUCAN follow: "../sensor_f9t.yaml" + - + type: "SensorModel" + name: "dynamic_model" + plugin: "core" processors: - @@ -58,18 +62,24 @@ config: sensor_name: "IMU_odometer" plugin: "imu" follow: "../processor_imu.yaml" - - - type: "ProcessorCompass" - name: "processor compass" - sensor_name: "compass" - plugin: "imu" - follow: "../processor_compass.yaml" + #- + # type: "ProcessorCompass" + # name: "processor compass" + # sensor_name: "compass" + # plugin: "imu" + # follow: "../processor_compass.yaml" - type: "ProcessorTrackerGnss" name: "processor gnss" sensor_name: "gnss" plugin: "gnss" follow: "processor_gnss.yaml" + - + type: "ProcessorFixWingModel" + name: "processor fix wing" + sensor_name: "dynamic_model" + plugin: "core" + follow: "processor_fix_wing.yaml" ROS subscriber: - @@ -84,12 +94,12 @@ config: sensor_name: "IMU_odometer" package: "wolf_ros_imu" follow: "subscriber_imu.yaml" - - - type: "SubscriberCompass" - topic: "/bno055_imu/magnetometer" - sensor_name: "compass" - package: "wolf_ros_imu" - follow: "subscriber_imu.yaml" + #- + # type: "SubscriberCompass" + # topic: "/bno055_imu/magnetometer" + # sensor_name: "compass" + # package: "wolf_ros_imu" + # follow: "subscriber_imu.yaml" - type: "SubscriberGnssFixPublisherEcef" topic: "/ublox_gps/fix" @@ -107,6 +117,18 @@ config: package: "wolf_ros_gauss" period: 0.1 sensor: "gnss" + - + type: "PublisherRpaStateInfo" + topic: "rpa_state_info" + package: "wolf_ros_gauss" + period: 0.5 + follow: "publisher_rpa_state_info.yaml" + - + type: "PublisherRpaPositioningInfo" + topic: "rpa_positioning_info" + package: "wolf_ros_gauss" + period: 0.5 + sensor: "gnss" - type: "PublisherPose" topic: "current_pose" @@ -138,7 +160,6 @@ config: topic: "graph" package: "wolf_ros_node" period: 0.2 - text_scale: 50 viz_scale: 50 - type: "PublisherTrackerGnssInfo" diff --git a/yaml/tucan/publisher_rpa_state_info.yaml b/yaml/tucan/publisher_rpa_state_info.yaml new file mode 100644 index 0000000000000000000000000000000000000000..4afdb2363e79b52f72d0036e14743226c61b995b --- /dev/null +++ b/yaml/tucan/publisher_rpa_state_info.yaml @@ -0,0 +1,8 @@ +topic_security: "/alarm_data" +sensor: "gnss" +icao: 3434009 # atlantic +k_H: 5.256522 +k_V: 4.891638 +HAL: 20 #20/10 +VAL: 30 #30/444 +yaw_offset: 0.0 \ No newline at end of file