From 3af88056f6c3a07216e1b1cfbb5a5ec7d95c980c Mon Sep 17 00:00:00 2001 From: joanvallve <jvallve@iri.upc.edu> Date: Fri, 12 Nov 2021 11:56:21 +0100 Subject: [PATCH] changing solver params and adding configs to tucan --- yaml/IRI/params.yaml | 12 +-- yaml/IRI/params_only_gnss.yaml | 10 +- yaml/IRI/solver.yaml | 16 +++ yaml/M600a/params.yaml | 12 +-- yaml/M600a/params_2.yaml | 10 +- yaml/M600a/params_3.yaml | 10 +- yaml/M600a/params_4.yaml | 10 +- yaml/M600a/params_only_gnss.yaml | 10 +- yaml/M600a/solver.yaml | 16 +++ yaml/M600b/params.yaml | 10 +- yaml/M600b/params_2.yaml | 10 +- yaml/M600b/params_3.yaml | 10 +- yaml/M600b/params_4.yaml | 10 +- yaml/M600b/params_only_gnss.yaml | 10 +- yaml/M600b/solver.yaml | 16 +++ yaml/atlantic/params.yaml | 10 +- yaml/atlantic/params_2.yaml | 10 +- yaml/atlantic/params_3.yaml | 10 +- yaml/atlantic/params_4.yaml | 10 +- yaml/atlantic/params_only_gnss.yaml | 10 +- yaml/atlantic/solver.yaml | 16 +++ yaml/scrab/params.yaml | 10 +- yaml/scrab/params_2.yaml | 10 +- yaml/scrab/params_3.yaml | 10 +- yaml/scrab/params_4.yaml | 10 +- yaml/scrab/params_only_gnss.yaml | 10 +- yaml/scrab/solver.yaml | 16 +++ yaml/tucan/params.yaml | 10 +- yaml/tucan/params_2.yaml | 161 ++++++++++++++++++++++++++++ yaml/tucan/params_3.yaml | 161 ++++++++++++++++++++++++++++ yaml/tucan/params_4.yaml | 161 ++++++++++++++++++++++++++++ yaml/tucan/processor_gnss.yaml | 2 +- yaml/tucan/processor_gnss_2.yaml | 45 ++++++++ yaml/tucan/processor_gnss_3.yaml | 45 ++++++++ yaml/tucan/processor_gnss_4.yaml | 45 ++++++++ yaml/tucan/solver.yaml | 16 +++ 36 files changed, 740 insertions(+), 210 deletions(-) create mode 100644 yaml/IRI/solver.yaml create mode 100644 yaml/M600a/solver.yaml create mode 100644 yaml/M600b/solver.yaml create mode 100644 yaml/atlantic/solver.yaml create mode 100644 yaml/scrab/solver.yaml create mode 100644 yaml/tucan/params_2.yaml create mode 100644 yaml/tucan/params_3.yaml create mode 100644 yaml/tucan/params_4.yaml create mode 100644 yaml/tucan/processor_gnss_2.yaml create mode 100644 yaml/tucan/processor_gnss_3.yaml create mode 100644 yaml/tucan/processor_gnss_4.yaml create mode 100644 yaml/tucan/solver.yaml diff --git a/yaml/IRI/params.yaml b/yaml/IRI/params.yaml index eec3d1e..6ae35fa 100644 --- a/yaml/IRI/params.yaml +++ b/yaml/IRI/params.yaml @@ -18,16 +18,8 @@ config: 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 - + follow: "solver.yaml" + map: type: "MapBase" plugin: "core" diff --git a/yaml/IRI/params_only_gnss.yaml b/yaml/IRI/params_only_gnss.yaml index f91af26..9d3485e 100644 --- a/yaml/IRI/params_only_gnss.yaml +++ b/yaml/IRI/params_only_gnss.yaml @@ -19,15 +19,7 @@ config: follow: "../prior/PO_fix.yaml" solver: - max_num_iterations: 20 - verbose: 0 - period: 0.0 - n_threads: 2 - update_immediately: true - min_num_iterations: 5 #if update immediately - compute_cov: false - cov_enum: 3 - cov_period: 1 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/IRI/solver.yaml b/yaml/IRI/solver.yaml new file mode 100644 index 0000000..bb6e89b --- /dev/null +++ b/yaml/IRI/solver.yaml @@ -0,0 +1,16 @@ +verbose: 0 +period: 0.0 +n_threads: 2 + +compute_cov: true +cov_enum: 3 +cov_period: 1 + +max_num_iterations: 20 +minimizer: "LEVENBERG_MARQUARDT" +update_immediately: false +min_num_iterations: 5 #if update_immediately +function_tolerance: 0.000001 +gradient_tolerance: 0.0000000001 +use_nonmonotonic_steps: false # if LEVENBERG_MARQUARDT or DOGLEG +max_consecutive_nonmonotonic_steps: 5 # if use_nonmonotonic_steps diff --git a/yaml/M600a/params.yaml b/yaml/M600a/params.yaml index d75a0a8..a6de98d 100644 --- a/yaml/M600a/params.yaml +++ b/yaml/M600a/params.yaml @@ -18,16 +18,8 @@ config: 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 - + follow: "solver.yaml" + map: type: "MapBase" plugin: "core" diff --git a/yaml/M600a/params_2.yaml b/yaml/M600a/params_2.yaml index 07916e0..0f7c4e6 100644 --- a/yaml/M600a/params_2.yaml +++ b/yaml/M600a/params_2.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600a/params_3.yaml b/yaml/M600a/params_3.yaml index d09eead..ebae724 100644 --- a/yaml/M600a/params_3.yaml +++ b/yaml/M600a/params_3.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600a/params_4.yaml b/yaml/M600a/params_4.yaml index 14a02de..2b9a7f6 100644 --- a/yaml/M600a/params_4.yaml +++ b/yaml/M600a/params_4.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600a/params_only_gnss.yaml b/yaml/M600a/params_only_gnss.yaml index 1573584..63ac9a9 100644 --- a/yaml/M600a/params_only_gnss.yaml +++ b/yaml/M600a/params_only_gnss.yaml @@ -18,15 +18,7 @@ config: follow: "../prior/PO_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: false - cov_enum: 3 - cov_period: 1 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600a/solver.yaml b/yaml/M600a/solver.yaml new file mode 100644 index 0000000..bb6e89b --- /dev/null +++ b/yaml/M600a/solver.yaml @@ -0,0 +1,16 @@ +verbose: 0 +period: 0.0 +n_threads: 2 + +compute_cov: true +cov_enum: 3 +cov_period: 1 + +max_num_iterations: 20 +minimizer: "LEVENBERG_MARQUARDT" +update_immediately: false +min_num_iterations: 5 #if update_immediately +function_tolerance: 0.000001 +gradient_tolerance: 0.0000000001 +use_nonmonotonic_steps: false # if LEVENBERG_MARQUARDT or DOGLEG +max_consecutive_nonmonotonic_steps: 5 # if use_nonmonotonic_steps diff --git a/yaml/M600b/params.yaml b/yaml/M600b/params.yaml index ec6df0e..c531a5a 100644 --- a/yaml/M600b/params.yaml +++ b/yaml/M600b/params.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600b/params_2.yaml b/yaml/M600b/params_2.yaml index 07916e0..0f7c4e6 100644 --- a/yaml/M600b/params_2.yaml +++ b/yaml/M600b/params_2.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600b/params_3.yaml b/yaml/M600b/params_3.yaml index d09eead..ebae724 100644 --- a/yaml/M600b/params_3.yaml +++ b/yaml/M600b/params_3.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600b/params_4.yaml b/yaml/M600b/params_4.yaml index 14a02de..2b9a7f6 100644 --- a/yaml/M600b/params_4.yaml +++ b/yaml/M600b/params_4.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600b/params_only_gnss.yaml b/yaml/M600b/params_only_gnss.yaml index f91af26..9c5684f 100644 --- a/yaml/M600b/params_only_gnss.yaml +++ b/yaml/M600b/params_only_gnss.yaml @@ -19,15 +19,7 @@ config: follow: "../prior/PO_fix.yaml" solver: - max_num_iterations: 20 - verbose: 0 - period: 0.0 - n_threads: 2 - update_immediately: true - min_num_iterations: 5 #if update immediately - compute_cov: false - cov_enum: 3 - cov_period: 1 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/M600b/solver.yaml b/yaml/M600b/solver.yaml new file mode 100644 index 0000000..bb6e89b --- /dev/null +++ b/yaml/M600b/solver.yaml @@ -0,0 +1,16 @@ +verbose: 0 +period: 0.0 +n_threads: 2 + +compute_cov: true +cov_enum: 3 +cov_period: 1 + +max_num_iterations: 20 +minimizer: "LEVENBERG_MARQUARDT" +update_immediately: false +min_num_iterations: 5 #if update_immediately +function_tolerance: 0.000001 +gradient_tolerance: 0.0000000001 +use_nonmonotonic_steps: false # if LEVENBERG_MARQUARDT or DOGLEG +max_consecutive_nonmonotonic_steps: 5 # if use_nonmonotonic_steps diff --git a/yaml/atlantic/params.yaml b/yaml/atlantic/params.yaml index 9680309..8f22514 100644 --- a/yaml/atlantic/params.yaml +++ b/yaml/atlantic/params.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/atlantic/params_2.yaml b/yaml/atlantic/params_2.yaml index 3ea8608..1750368 100644 --- a/yaml/atlantic/params_2.yaml +++ b/yaml/atlantic/params_2.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/atlantic/params_3.yaml b/yaml/atlantic/params_3.yaml index b1de5d6..e19cf29 100644 --- a/yaml/atlantic/params_3.yaml +++ b/yaml/atlantic/params_3.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/atlantic/params_4.yaml b/yaml/atlantic/params_4.yaml index 0190769..e7fd94d 100644 --- a/yaml/atlantic/params_4.yaml +++ b/yaml/atlantic/params_4.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/atlantic/params_only_gnss.yaml b/yaml/atlantic/params_only_gnss.yaml index 225a486..1e9e851 100644 --- a/yaml/atlantic/params_only_gnss.yaml +++ b/yaml/atlantic/params_only_gnss.yaml @@ -19,15 +19,7 @@ config: follow: "../prior/PO_fix.yaml" solver: - max_num_iterations: 20 - verbose: 0 - period: 0.0 - n_threads: 2 - update_immediately: true - min_num_iterations: 5 #if update immediately - compute_cov: false - cov_enum: 3 - cov_period: 1 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/atlantic/solver.yaml b/yaml/atlantic/solver.yaml new file mode 100644 index 0000000..bb6e89b --- /dev/null +++ b/yaml/atlantic/solver.yaml @@ -0,0 +1,16 @@ +verbose: 0 +period: 0.0 +n_threads: 2 + +compute_cov: true +cov_enum: 3 +cov_period: 1 + +max_num_iterations: 20 +minimizer: "LEVENBERG_MARQUARDT" +update_immediately: false +min_num_iterations: 5 #if update_immediately +function_tolerance: 0.000001 +gradient_tolerance: 0.0000000001 +use_nonmonotonic_steps: false # if LEVENBERG_MARQUARDT or DOGLEG +max_consecutive_nonmonotonic_steps: 5 # if use_nonmonotonic_steps diff --git a/yaml/scrab/params.yaml b/yaml/scrab/params.yaml index 1b723684..62788b4 100644 --- a/yaml/scrab/params.yaml +++ b/yaml/scrab/params.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/scrab/params_2.yaml b/yaml/scrab/params_2.yaml index 18d4a8e..6c5ce3c 100644 --- a/yaml/scrab/params_2.yaml +++ b/yaml/scrab/params_2.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/scrab/params_3.yaml b/yaml/scrab/params_3.yaml index 2356290..23762d7 100644 --- a/yaml/scrab/params_3.yaml +++ b/yaml/scrab/params_3.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/scrab/params_4.yaml b/yaml/scrab/params_4.yaml index 25bde87..83f2006 100644 --- a/yaml/scrab/params_4.yaml +++ b/yaml/scrab/params_4.yaml @@ -18,15 +18,7 @@ config: 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 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/scrab/params_only_gnss.yaml b/yaml/scrab/params_only_gnss.yaml index f91af26..9c5684f 100644 --- a/yaml/scrab/params_only_gnss.yaml +++ b/yaml/scrab/params_only_gnss.yaml @@ -19,15 +19,7 @@ config: follow: "../prior/PO_fix.yaml" solver: - max_num_iterations: 20 - verbose: 0 - period: 0.0 - n_threads: 2 - update_immediately: true - min_num_iterations: 5 #if update immediately - compute_cov: false - cov_enum: 3 - cov_period: 1 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/scrab/solver.yaml b/yaml/scrab/solver.yaml new file mode 100644 index 0000000..bb6e89b --- /dev/null +++ b/yaml/scrab/solver.yaml @@ -0,0 +1,16 @@ +verbose: 0 +period: 0.0 +n_threads: 2 + +compute_cov: true +cov_enum: 3 +cov_period: 1 + +max_num_iterations: 20 +minimizer: "LEVENBERG_MARQUARDT" +update_immediately: false +min_num_iterations: 5 #if update_immediately +function_tolerance: 0.000001 +gradient_tolerance: 0.0000000001 +use_nonmonotonic_steps: false # if LEVENBERG_MARQUARDT or DOGLEG +max_consecutive_nonmonotonic_steps: 5 # if use_nonmonotonic_steps diff --git a/yaml/tucan/params.yaml b/yaml/tucan/params.yaml index ae8771c..c959755 100644 --- a/yaml/tucan/params.yaml +++ b/yaml/tucan/params.yaml @@ -18,15 +18,7 @@ config: 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: 4 #GAUSS_TUCAN - cov_period: 1 + follow: "solver.yaml" map: type: "MapBase" diff --git a/yaml/tucan/params_2.yaml b/yaml/tucan/params_2.yaml new file mode 100644 index 0000000..dc94801 --- /dev/null +++ b/yaml/tucan/params_2.yaml @@ -0,0 +1,161 @@ +config: + debug: + profiling: true + profiling_file: "~/profiling_tucan.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: + follow: "solver.yaml" + + 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.30, 0, -0.05] # TUCAN + 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: 5 + period: 0.2 + max_points: 10000 + + ROS publisher: + - + type: "PublisherUbxNavPVT" + topic: "/ublox_emulator/nav_pvt9" + 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" + package: "wolf_ros_node" + marker_color: [1,0,0,1] + line_size: 5 + 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: 50 + - + 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/tucan/params_3.yaml b/yaml/tucan/params_3.yaml new file mode 100644 index 0000000..c453c8d --- /dev/null +++ b/yaml/tucan/params_3.yaml @@ -0,0 +1,161 @@ +config: + debug: + profiling: true + profiling_file: "~/profiling_tucan.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: + follow: "solver.yaml" + + 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.30, 0, -0.05] # TUCAN + 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: 5 + period: 0.2 + max_points: 10000 + + ROS publisher: + - + type: "PublisherUbxNavPVT" + topic: "/ublox_emulator/nav_pvt9" + 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" + package: "wolf_ros_node" + marker_color: [1,0,0,1] + line_size: 5 + 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: 50 + - + 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/tucan/params_4.yaml b/yaml/tucan/params_4.yaml new file mode 100644 index 0000000..c453c8d --- /dev/null +++ b/yaml/tucan/params_4.yaml @@ -0,0 +1,161 @@ +config: + debug: + profiling: true + profiling_file: "~/profiling_tucan.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: + follow: "solver.yaml" + + 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.30, 0, -0.05] # TUCAN + 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: 5 + period: 0.2 + max_points: 10000 + + ROS publisher: + - + type: "PublisherUbxNavPVT" + topic: "/ublox_emulator/nav_pvt9" + 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" + package: "wolf_ros_node" + marker_color: [1,0,0,1] + line_size: 5 + 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: 50 + - + 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/tucan/processor_gnss.yaml b/yaml/tucan/processor_gnss.yaml index 8712d1a..f9016bd 100644 --- a/yaml/tucan/processor_gnss.yaml +++ b/yaml/tucan/processor_gnss.yaml @@ -24,7 +24,7 @@ gnss: constellations: GPS: true SBS: false - GLO: true + GLO: false GAL: true QZS: false CMP: false diff --git a/yaml/tucan/processor_gnss_2.yaml b/yaml/tucan/processor_gnss_2.yaml new file mode 100644 index 0000000..0af7399 --- /dev/null +++ b/yaml/tucan/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/tucan/processor_gnss_3.yaml b/yaml/tucan/processor_gnss_3.yaml new file mode 100644 index 0000000..0483aec --- /dev/null +++ b/yaml/tucan/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/tucan/processor_gnss_4.yaml b/yaml/tucan/processor_gnss_4.yaml new file mode 100644 index 0000000..25c554a --- /dev/null +++ b/yaml/tucan/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/solver.yaml b/yaml/tucan/solver.yaml new file mode 100644 index 0000000..1c191d0 --- /dev/null +++ b/yaml/tucan/solver.yaml @@ -0,0 +1,16 @@ +verbose: 0 +period: 0.0 +n_threads: 2 + +compute_cov: true +cov_enum: 4 #GAUSS_TUCAN +cov_period: 1 + +max_num_iterations: 20 +minimizer: "LEVENBERG_MARQUARDT" +update_immediately: false +min_num_iterations: 5 #if update_immediately +function_tolerance: 0.000001 +gradient_tolerance: 0.0000000001 +use_nonmonotonic_steps: false # if LEVENBERG_MARQUARDT or DOGLEG +max_consecutive_nonmonotonic_steps: 5 # if use_nonmonotonic_steps -- GitLab