forked from LORD-MicroStrain/microstrain_inertial
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathcv7_ins.yml
48 lines (38 loc) · 2.42 KB
/
cv7_ins.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
# 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 : 'cv7_ins_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
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
# We will use auto relative position configuration for this example. This configuration does a couple things:
# We will setup a local tangent plane at the first location we receive after the device enters full navigation mode
# We will publish this location as the transform from the earth_frame_id to map_frame_id frame
filter_relative_position_config : True
filter_relative_position_source : 2
# This will set the initial heading alignment to use GNSS Kinematic Alignment
# Note that if you have any form of external heading, it is probably better to set this to 8 in order to use that
filter_auto_heading_alignment_selector : 2
# Setup some aiding options.
filter_enable_gnss_pos_vel_aiding : True
filter_enable_gnss_heading_aiding : False
# This example shows a very basic setup with no PPS sync, so the PPS will be generated by the device's oscillator for drift constaint
# Note that if you have any way to provide a more accurate PPS ex: GNSS, you should connect and configure PPS accordingly
filter_pps_source : 4
# Disable the filter declination source. This is required to get the node to start, and isn't doing anything special
filter_declination_source : 1
# Subscribe to the aiding messages.
# For this example we are just subscribing to external GNSS position and velocity
subscribe_ext_fix : True
subscribe_ext_vel_enu : True