diff --git a/launch/imu2d_demo.launch b/launch/imu2d_demo.launch index 22392b14c01d96474ea7160f5d24ffb6ed870e3e..7d5a13654a7adbe5cc9118419e018df7f1f44b17 100644 --- a/launch/imu2d_demo.launch +++ b/launch/imu2d_demo.launch @@ -12,27 +12,27 @@ <arg name="launch_pref" value="gdb -ex run --args" if="$(arg gdb)" /> <!-- using "clock" option to use the simulated time. Rosbag launch as the first node --> - <node pkg="rostopic" type="rostopic" name="" args='pub /ana/sensors/bno055_imu/imu/topic_enable std_msgs/Bool "data: True"'/> + <node pkg="rostopic" type="rostopic" name="" args='pub /helena/sensors/bno055_imu/imu/topic_enable std_msgs/Bool "data: True"'/> <node pkg="tf" type="static_transform_publisher" name="static_tf" - args="0 0 0 0 0 0 /ana/base_footprint /ana/base_link 100"/> + args="0 0 0 0 0 0 /helena/base_footprint /helena/base_link 100"/> <node pkg="tf" type="static_transform_publisher" name="static_tf2" - args="0 0 0 0 0 0 /ana/base_link /ana/imu_bno055 100"/> + args="0 0 0 0 0 0 /helena/base_link /helena/imu_bno055 100"/> <node pkg="tf" type="static_transform_publisher" name="static_tf3" - args="0 0 0 3.14159265 0 0 /ana/base_link /ana/velodyne 100"/> + args="0 0 0 3.14159265 0 0 /helena/base_link /helena/velodyne 100"/> <node pkg="tf" type="static_transform_publisher" name="static_tf4" - args="-0.11 0.01 0 0 0 0 /ana/base_link /ana/imu_microstrain 100"/> + args="-0.11 0.01 0 0 0 0 /helena/base_link /helena/imu_microstrain 100"/> <node pkg="rosbag" type="play" diff --git a/rviz/imu2d_demo.rviz b/rviz/imu2d_demo.rviz index 1141bab5157198a3b78cd07fb9f274e7874cf246..947506c5c96f62226c02d7cbea8512bb08725351 100644 --- a/rviz/imu2d_demo.rviz +++ b/rviz/imu2d_demo.rviz @@ -6,19 +6,19 @@ Panels: Expanded: - /Global Options1 - /TF1 - - /TF1/Frames1 - /TF1/Tree1 - /Odometry1/Shape1 - /LaserScan1 - /Landmarks1 - /Factors1 + - /Factors1/Status1 - /Factors1/Namespaces1 - /Trajectory1 - /Trajectory1/Namespaces1 - /Axes1 - /PointCloud21 - /Imu1 - Splitter Ratio: 0.6038647294044495 + Splitter Ratio: 0.5285326242446899 Tree Height: 728 - Class: rviz/Selection Name: Selection @@ -69,28 +69,78 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: false - ana/base_footprint: + helena/base_footprint: Value: true - ana/base_footprint_robot: - Value: false - ana/base_link: - Value: false - ana/front_left_axle: - Value: false - ana/front_right_axle: - Value: false - ana/imu_bno055: - Value: false - ana/imu_microstrain: - Value: false - ana/odom: + helena/base_link: + Value: true + helena/camera_bottom_screw_frame: + Value: true + helena/camera_color_frame: + Value: true + helena/camera_color_optical_frame: + Value: true + helena/camera_depth_frame: + Value: true + helena/camera_depth_optical_frame: + Value: true + helena/camera_infra1_frame: + Value: true + helena/camera_infra1_optical_frame: + Value: true + helena/camera_infra2_frame: + Value: true + helena/camera_infra2_optical_frame: + Value: true + helena/camera_link: + Value: true + helena/front_left_axle: + Value: true + helena/front_left_hub: + Value: true + helena/front_left_wheel: + Value: true + helena/front_right_axle: + Value: true + helena/front_right_hub: + Value: true + helena/front_right_wheel: + Value: true + helena/front_sonar: + Value: true + helena/helena_box: + Value: true + helena/helena_realsense_support: + Value: true + helena/imu_bno055: + Value: true + helena/imu_bno055_base: + Value: true + helena/imu_microstrain: + Value: true + helena/odom: + Value: true + helena/rear_left_axle: + Value: true + helena/rear_left_hub: + Value: true + helena/rear_left_wheel: + Value: true + helena/rear_right_axle: + Value: true + helena/rear_right_hub: + Value: true + helena/rear_right_wheel: + Value: true + helena/rear_sonar: + Value: true + helena/robosense: + Value: true + helena/robosense_base: + Value: true + helena/top_plate: + Value: true + helena/velodyne: Value: true - ana/rear_left_axle: - Value: false - ana/rear_right_axle: - Value: false - ana/velodyne: - Value: false map: Value: false Marker Scale: 1 @@ -100,25 +150,58 @@ Visualization Manager: Show Names: true Tree: map: - ana/odom: - ana/base_footprint: - ana/base_link: - ana/front_left_axle: - {} - ana/front_right_axle: + helena/odom: + helena/base_footprint: + helena/base_link: + helena/front_left_axle: + helena/front_left_hub: + helena/front_left_wheel: + {} + helena/front_right_axle: + helena/front_right_hub: + helena/front_right_wheel: + {} + helena/front_sonar: {} - ana/imu_bno055: + helena/imu_bno055: {} - ana/imu_microstrain: + helena/imu_microstrain: {} - ana/rear_left_axle: + helena/rear_left_axle: + helena/rear_left_hub: + helena/rear_left_wheel: + {} + helena/rear_right_axle: + helena/rear_right_hub: + helena/rear_right_wheel: + {} + helena/rear_sonar: {} - ana/rear_right_axle: + helena/top_plate: + helena/helena_box: + {} + helena/helena_realsense_support: + helena/camera_bottom_screw_frame: + helena/camera_link: + helena/camera_color_frame: + helena/camera_color_optical_frame: + {} + helena/camera_depth_frame: + helena/camera_depth_optical_frame: + {} + helena/camera_infra1_frame: + helena/camera_infra1_optical_frame: + {} + helena/camera_infra2_frame: + helena/camera_infra2_optical_frame: + {} + helena/robosense_base: + helena/robosense: + {} + helena/velodyne: {} - ana/velodyne: - {} - ana/base_footprint_robot: - {} + helena/imu_bno055_base: + {} Update Interval: 0 Value: true - Angle Tolerance: 0.10000000149011612 @@ -167,7 +250,7 @@ Visualization Manager: Color: 250; 84; 255 Color Transformer: FlatColor Decay Time: 100 - Enabled: false + Enabled: true Invert Rainbow: false Max Color: 255; 255; 255 Min Color: 0; 0; 0 @@ -178,11 +261,11 @@ Visualization Manager: Size (Pixels): 3 Size (m): 0.05999999865889549 Style: Flat Squares - Topic: /ana/sensors/scan + Topic: /helena/sensors/scan Unreliable: false Use Fixed Frame: true Use rainbow: true - Value: false + Value: true - Class: rviz/MarkerArray Enabled: false Marker Topic: /wolf_ros_node/graph_landmarks @@ -196,30 +279,27 @@ Visualization Manager: Marker Topic: /wolf_ros_node/graph_factors Name: Factors Namespaces: - factors_processorimu2dbno: true factors_processorodom2d: true factors_processorodomicp: true - factors_text_processorimu2dbno: false factors_text_processorodom2d: false factors_text_processorodomicp: false - factors_text_unnamed_processor: false - factors_unnamed_processor: true Queue Size: 100 Value: true - Class: rviz/MarkerArray - Enabled: false + Enabled: true Marker Topic: /wolf_ros_node/graph_trajectory Name: Trajectory Namespaces: - {} + frames: true + frames_text: true Queue Size: 100 - Value: false + Value: true - Class: rviz/Axes Enabled: true Length: 1 Name: Axes Radius: 0.10000000149011612 - Reference Frame: ana/base_link + Reference Frame: helena/base_link Value: true - Alpha: 1 Autocompute Intensity Bounds: true @@ -262,12 +342,12 @@ Visualization Manager: - Alpha: 1 Class: rviz_plugin_tutorials/Imu Color: 204; 51; 204 - Enabled: false + Enabled: true History Length: 1 Name: Imu - Topic: /ana/imu/data_remapped + Topic: /helena/sensors/bno055_imu/imu_remapped Unreliable: false - Value: false + Value: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -296,25 +376,25 @@ Visualization Manager: Views: Current: Class: rviz/Orbit - Distance: 14.700403213500977 + Distance: 25.464996337890625 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 2.423039674758911 - Y: -1.9012470245361328 - Z: 1.0024703741073608 + X: 0.7309823632240295 + Y: -0.0005876626819372177 + Z: 1.5242977142333984 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.5947971940040588 + Pitch: 0.7247968912124634 Target Frame: map Value: Orbit (rviz) - Yaw: 4.008172988891602 + Yaw: 5.4131693840026855 Saved: - Angle: 0 Class: rviz/TopDownOrtho @@ -367,7 +447,7 @@ Window Geometry: Height: 1025 Hide Left Dock: false Hide Right Dock: true - QMainWindow State: 000000ff00000000fd00000004000000000000027f00000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004b80000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + QMainWindow State: 000000ff00000000fd0000000400000000000002e200000363fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000363000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073000000002800000396000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073d0000003efc0100000002fb0000000800540069006d006501000000000000073d000002eb00fffffffb0000000800540069006d00650100000000000004500000000000000000000004550000036300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 Selection: collapsed: false Time: diff --git a/yaml/imu2d_test1.yaml b/yaml/imu2d_test1.yaml index b1c8aa72f7f7c4f1a709eb1505fbecf25562d2ab..b674e10644b8d88ce3176dfb00c4efa2f711f664 100644 --- a/yaml/imu2d_test1.yaml +++ b/yaml/imu2d_test1.yaml @@ -49,16 +49,16 @@ config: name: "scanner_front_left" plugin: "laser" follow: "test_laser_params.yaml" + #- + # type: "SensorImu2d" + # name: "bno" + # plugin: "imu" + # follow: "test_imu_params.yaml" - type: "SensorImu2d" - name: "bno" + name: "microstrain" plugin: "imu" follow: "test_imu_params.yaml" - #- - # type: "SensorImu2d" - # name: "microstrain" - # plugin: "imu" - # follow: "test_imu_params.yaml" processors: - @@ -73,38 +73,38 @@ config: sensor_name: "scanner_front_left" plugin: "laser" follow: "test_laser_processor.yaml" + #- + # type: "ProcessorImu2d" + # name: "processorimu2dbno" + # sensor_name: "bno" + # plugin: "imu" + # follow: "test_imu_processor.yaml" - type: "ProcessorImu2d" - name: "processorimu2dbno" - sensor_name: "bno" + name: "processorimu2dmicro" + sensor_name: "microstrain" plugin: "imu" follow: "test_imu_processor.yaml" - #- - # type: "ProcessorImu2d" - # name: "processorimu2dmicro" - # sensor_name: "microstrain" - # plugin: "imu" - # follow: "test_imu_processor.yaml" ROS subscriber: - package: "wolf_ros_node" type: "SubscriberOdom2d" - topic: "/ana/odom" + topic: "/helena/odom" sensor_name: "odom2d" - package: "wolf_ros_laser" type: "SubscriberLaser2d" - topic: "/ana/sensors/scan" + topic: "/helena/sensors/scan" sensor_name: "scanner_front_left" load_params_from_msg: true - package: "wolf_ros_imu" type: "SubscriberImuEnableable" - topic: "/ana/sensors/bno055_imu/imu" - sensor_name: "bno" - #topic: "/ana/imu/data" - #sensor_name: "microstrain" + #topic: "/helena/sensors/bno055_imu/imu" + #sensor_name: "bno" + topic: "/helena/sensors/imu/data" + sensor_name: "microstrain" follow: "test_imu_subscriber.yaml" ROS publisher: diff --git a/yaml/imu2d_test7.yaml b/yaml/imu2d_test7.yaml new file mode 100644 index 0000000000000000000000000000000000000000..b0fa2cbc4d3ae2b5a9d97cac4b808db1a2374c53 --- /dev/null +++ b/yaml/imu2d_test7.yaml @@ -0,0 +1,129 @@ +config: + debug: + profiling: true + profiling_file: "~/wolf_demo_profiling_imu2d_test7.txt" + print_problem: false + print_period: 5 + print_depth: 4 + print_constr_by: false + print_metric: true + print_state_blocks: true + problem: + tree_manager: + type: "none" + frame_structure: "POV" + dimension: 2 + prior: + mode: "fix" + $state: + P: [0,0] + O: [0] + V: [0,0] + time_tolerance: 0.1 + node_rate: 100 + map: + type: "MapBase" + plugin: "core" + + solver: + max_num_iterations: 10 + verbose: 0 + period: 0 + update_immediately: false + n_threads: 2 + compute_cov: false + function_tolerance: 1e-6 + gradient_tolerance: 1e-6 + minimizer: "LEVENBERG_MARQUARDT" + use_nonmonotonic_steps: False + max_consecutive_nonmonotonic_steps: 10 + + sensors: + - + type: "SensorLaser2d" + name: "scanner_front_left" + plugin: "laser" + follow: "test_laser_params.yaml" + - + type: "SensorGnss" + name: "gnss" + plugin: "gnss" + follow: "test_gnss_params.yaml" + + processors: + - + type: "ProcessorOdomIcp" + name: "processorodomicp" + sensor_name: "scanner_front_left" + plugin: "laser" + follow: "test_laser_processor.yaml" + - + type: "ProcessorTrackerGnss" + name: "processorgnss" + sensor_name: "gnss" + plugin: "gnss" + follow: "test_gnss_processor.yaml" + + ROS subscriber: + - + package: "wolf_ros_node" + type: "SubscriberOdom2d" + topic: "/helena/odom" + sensor_name: "odom2d" + - + package: "wolf_ros_laser" + type: "SubscriberLaser2d" + topic: "/helena/sensors/scan" + sensor_name: "scanner_front_left" + load_params_from_msg: true + - + package: "wolf_ros_gnss" + type: "SubscriberGnssUblox" + topic: "/helena/sensors/ublox_gps/raw_data_stream" + sensor_name: "gnss" + follow: "test_subscriber_gnss.yaml" + + ROS publisher: + - + package: "wolf_ros_node" + type: "PublisherTf" + topic: " " + period: 0.1 + follow: "test_publisher_ros_node.yaml" + - + package: "wolf_ros_node" + type: "PublisherGraph" + topic: "graph" + period: 1 + viz_overlapped_factors: true + - + package: "wolf_ros_node" + type: "PublisherPose" + topic: "current_pose" + marker_color: [1,0,0,1] + period: 0.01 + extrinsics: false + frame_id: "ENU" + - + package: "wolf_ros_laser" + type: "PublisherLaserMap" + topic: "map" + period: 1 + map_frame_id: "map" + update_dist_th: 0.05 + update_angle_th: 0.05 + max_n_cells: 1000000 + grid_size: 0.1 + p_free: 0.3 + p_obst: 0.8 + p_free_th: 0.2 + p_obst_th: 0.9 + discard_max_range: true + - + package: "wolf_ros_gnss" + type: "PublisherGnssTf" + topic: " " + period: 0.1 + sensor_gnss_name: "gnss" + + diff --git a/yaml/test_gnss_params.yaml b/yaml/test_gnss_params.yaml new file mode 100644 index 0000000000000000000000000000000000000000..34bf6392396adf18201431c10720ffbccbb03396 --- /dev/null +++ b/yaml/test_gnss_params.yaml @@ -0,0 +1,13 @@ +extrinsic: + pose: [0, 0, 0] +extrinsics_fixed: true +clock_bias_GPS_GLO_dynamic: false +clock_bias_GPS_GAL_dynamic: false +clock_bias_GPS_CMP_dynamic: false +ENU: + mode: "auto" + roll_fixed: true + pitch_fixed: true + yaw_fixed: true + translation_fixed: true + diff --git a/yaml/test_gnss_processor.yaml b/yaml/test_gnss_processor.yaml new file mode 100644 index 0000000000000000000000000000000000000000..1bbc9b1dcee724afb2a84b2e891325219fa7c416 --- /dev/null +++ b/yaml/test_gnss_processor.yaml @@ -0,0 +1,47 @@ +time_tolerance: 0.1 +apply_loss_function: false +min_features_for_keyframe: 0 #4 +max_new_features: -1 #unlimited +remove_outliers: true +remove_outliers_with_fix: true +outlier_residual_th: 10 +init_frames: false +pseudo_ranges: true +enu_map_fix_dist: 5 +fix: false +keyframe_vote: + voting_active: true + max_time_span: 1 + min_features_for_keyframe: 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: true + QZS: false + CMP: false + IRN: false + LEO: false + tdcp: + enabled: true + corr_iono: true + corr_tropo: true + corr_clock: true + loss_function: false + time_window: 100 # s + sigma_atm: 0.0016 # m/sqrt(s) + sigma_carrier: 0.0011 # m + multi_freq: false + remove_outliers: false + batch: false + structure: first-all + diff --git a/yaml/test_imu_params.yaml b/yaml/test_imu_params.yaml index def81eeb85c4b81bfbcc4b8df44e1362961ff193..70f8799fa9290a55fc126a629ce3f728f10c1cde 100644 --- a/yaml/test_imu_params.yaml +++ b/yaml/test_imu_params.yaml @@ -1,20 +1,20 @@ -#bno +##bno +#extrinsic: +# pose: [0,0,0] +#a_noise: 0.096 #best: 0.96 +#w_noise: 0.02 +#ab_initial_stdev: 5 # m/s2 - initial bias +#wb_initial_stdev: 1 # rad/sec - initial bias +#ab_rate_stdev: 0.0001 # m/s2/sqrt(s) +#wb_rate_stdev: 0.0001 # rad/s/sqrt(s) +#orthogonal_gravity: true +#microstrain extrinsic: pose: [0,0,0] -a_noise: 0.096 #best: 0.96 -w_noise: 0.02 -ab_initial_stdev: 5 # m/s2 - initial bias -wb_initial_stdev: 1 # rad/sec - initial bias +a_noise: 0.900 +w_noise: 0.01 +ab_initial_stdev: 0.5 # m/s2 - initial bias +wb_initial_stdev: 0.1 # rad/sec - initial bias ab_rate_stdev: 0.0001 # m/s2/sqrt(s) wb_rate_stdev: 0.0001 # rad/s/sqrt(s) orthogonal_gravity: true -#microstrain -#extrinsic: -# pose: [0,0,0] -#a_noise: 0.900 -#w_noise: 0.01 -#ab_initial_stdev: 0.5 # m/s2 - initial bias -#wb_initial_stdev: 0.1 # rad/sec - initial bias -#ab_rate_stdev: 0.00001 # m/s2/sqrt(s) -#wb_rate_stdev: 0.00001 # rad/s/sqrt(s) -#orthogonal_gravity: true diff --git a/yaml/test_imu_processor.yaml b/yaml/test_imu_processor.yaml index 9968f054bb3c92c47bc73b4bf49898231d5acb6e..dd3cdd5b2635b12639c4c5a3fe62b67f57ea319a 100644 --- a/yaml/test_imu_processor.yaml +++ b/yaml/test_imu_processor.yaml @@ -1,5 +1,5 @@ -time_tolerance: 0.008 #Half the sample time, bno -# time_tolerance: 0.005 #Half the sample time, microstrain +#time_tolerance: 0.008 #Half the sample time, bno +time_tolerance: 0.005 #Half the sample time, microstrain unmeasured_perturbation_std: 0.1 keyframe_vote: voting_active: true diff --git a/yaml/test_laser_processor.yaml b/yaml/test_laser_processor.yaml index 06847e9355446b14a201ee058fd0c5617f027897..d2aaceeee6da6c882b2965f3a7ef20989d812cf8 100644 --- a/yaml/test_laser_processor.yaml +++ b/yaml/test_laser_processor.yaml @@ -9,7 +9,7 @@ keyframe_vote: max_new_features: 15 follow: "csm.yaml" time_tolerance: 0.05 #Half the sample time -state_getter: false +state_getter: true state_priority: 10 apply_loss_function: false initial_guess: "state" diff --git a/yaml/test_publisher_ros_node.yaml b/yaml/test_publisher_ros_node.yaml index a3e37459266db719cbea053e906bc686d902fec3..b4abe64574d3775edbfa5182497f268a82947ac4 100644 --- a/yaml/test_publisher_ros_node.yaml +++ b/yaml/test_publisher_ros_node.yaml @@ -1,4 +1,4 @@ map_frame_id: "map" -odom_frame_id: "ana/odom" -base_frame_id: "ana/base_footprint" +odom_frame_id: "helena/odom" +base_frame_id: "helena/base_footprint" publish_odom_tf: false diff --git a/yaml/test_subscriber_gnss.yaml b/yaml/test_subscriber_gnss.yaml new file mode 100644 index 0000000000000000000000000000000000000000..971b0b7f06c7162428e76ef930d98202088ffbd0 --- /dev/null +++ b/yaml/test_subscriber_gnss.yaml @@ -0,0 +1,23 @@ +process_not_available: false +reset_receiver: false +publish_fix: +enabled: true +topic: "RTKLIB_fix" +gnss_options: + sateph: 6 # satellite ephemeris/clock (0:broadcast ephemeris,1:precise ephemeris,2:broadcast + SBAS,3:ephemeris option: broadcast + SSR_APC,4:broadcast + SSR_COM,5: QZSS LEX ephemeris + ionoopt: 9 # ionosphere option (0:correction off,1:broadcast mode,2:SBAS model,3:L1/L2 or L1/L5,4:estimation,5:IONEX TEC model,6:QZSS broadcast,7:QZSS LEX ionosphere,8:SLANT TEC mode) + 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 n times + elmin: 0.26 # elevation min (rad) = 15 degrees + maxgdop: 30 # reject threshold of gdop (ground dilusion of precision) + constellations: + GPS: true + SBS: false + GLO: false + GAL: true + QZS: false + CMP: false + IRN: false + LEO: false + diff --git a/yaml/tests.txt b/yaml/tests.txt index 17350ce9403c82c7c85d40489182f86273a94ef6..de48fec6ceb846de6396a743a168ca70ef0278c5 100644 --- a/yaml/tests.txt +++ b/yaml/tests.txt @@ -10,3 +10,6 @@ test5 laser + imu test6: laser + odom + +test7: + laser + gnss