forked from ros-drivers/microstrain_mips
-
Notifications
You must be signed in to change notification settings - Fork 78
/
Copy pathgq7.yml
100 lines (80 loc) · 4.72 KB
/
gq7.yml
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
# You should change this section of config to match your setup
port : '/dev/microstrain_main'
baudrate : 115200
# This will cause the node to convert any NED measurements to ENU
# This will also cause the node to convert any vehicle frame measurements to the ROS definition of a vehicle frame
use_enu_frame : True
# Configure some frame IDs
frame_id : 'gq7_link' # Frame ID of all of the filter messages. Represents the location of the CV7-INS in the tf tree
map_frame_id : "map" # Frame ID of the local tangent plane.
earth_frame_id : "earth" # Frame ID of the global frame
gnss1_frame_id : "gq7_gnss_1_antenna_link"
gnss2_frame_id : "gq7_gnss_2_antenna_link"
odometer_frame_id : "gq7_odometer_link"
target_frame_id : "base_link" # Frame ID that we will publish a transform to.
# Disable the transform from the mount to frame id transform as it will be handled in the launch file
publish_mount_to_frame_id_transform : False
# We will use relative transform mode, meaning that we will publish the following transforms from this node
# earth_frame_id -> map_frame_id
# map_frame_id -> target_frame_id
# This helps ROS standard tools consume and display position information produced by the device
tf_mode: 2
# Enable the RTK dongle interface for communication with the 3DM-RTK.
# Note: Even if you do not have a 3DM-RTK connected to the aux port, this boolean can remain true
rtk_dongle_enable : True
# We will use base station relative position configuration for this example. This configuration does a couple things:
# We will setup a local tangent plane at the location of the RTK base station being used by the GQ7.
# We will publish this location as the transform from the earth_frame_id to map_frame_id frame
# Note: This configuration requires a 3DM-RTK to be connected to the aux port of the GQ7.
# If you do not have that device, see https://wiki.ros.org/microstrain_inertial_driver/relative_position_configuration for more options.
filter_relative_position_config : True
filter_relative_position_source : 2
# Set the antenna offsets.
# Note: These should be changed for you setup, otherwise dual antenna heading will not initialize.
gnss1_antenna_offset : [0.0, -0.7, -1.0]
gnss2_antenna_offset : [0.0, 0.7, -1.0]
# This will set the heading alignment to be dual antenna
filter_auto_heading_alignment_selector : 1
# This will contain the raw IMU data, NOT the filtered IMU data
imu_data_rate : 100
# The default is to publish LLH position and velocity, but rviz has a hard time displaying that.
# Instead we will publish the position in the ECEF frame
gnss1_llh_position_data_rate : 0
gnss1_velocity_data_rate : 0
gnss1_odometry_earth_data_rate : 2
gnss2_llh_position_data_rate : 0
gnss2_velocity_data_rate : 0
gnss2_odometry_earth_data_rate : 2
# We will only publish the odometry messages from the filter in this example.
# Also publish the human readable message which can be echoed from the command line
filter_human_readable_status_data_rate : 1
filter_odometry_earth_data_rate : 10
filter_odometry_map_data_rate : 10
# Turning on this will cause the transform between gq7_link and gnss_1_antenna_link/gnss_2_antenna_link to be updated from the filter
mip_filter_multi_antenna_offset_correction_data_rate : 2
#################################################################################################################
# Optional odometer config. Useful if using a wheeled vehicle with a wheel encoder connected to the GQ7 over GPIO
# This configuration will not cause any issues if you do not have an odometer connected
#################################################################################################################
# Enable the hardware odometer
enable_hardware_odometer : True
odometer_scaling : 1.0
odometer_uncertainty : 0.15
# Allow the filter to use the hardware odometer in it's estimates
filter_enable_odometer_aiding : True
# For this example, we will assume that we are in a wheeled vehicle such as a car.
# Setting this option will give us better heading performance especially in GNSS outages
# If you are operating in a non wheeled vehicle make sure to disable this
filter_enable_wheeled_vehicle_constraint : True
# Set the location of the odometer
# Note: These should be changed for you setup
filter_speed_lever_arm : [0.0, 0.0, 0.0]
# This GPIO config is specific to this setup, and requires that you use GPIO pins 1 and 2 for encoder A and B respectively.
# You should update for your setup appropriately
gpio_config : True
gpio1_feature : 3 # ENCODER feature
gpio1_behavior : 1 # ENCODER_A behavior
gpio1_pin_mode : 0 # NONE pin_mode
gpio2_feature : 3 # ENCODER feature
gpio2_behavior : 2 # ENCODER_B behavior
gpio2_pin_mode : 0 # NONE pin_mode