# NOTE: This file is formatted to work with ROS and will not work if specified as the params_file argument in ROS2.
# If you want to override parameters for ROS2, start with https://github.com/LORD-MicroStrain/microstrain_inertial/blob/ros2/microstrain_inertial_driver/config/empty.yml
# port is the main port that the device will communicate over. For all devices except the GQ7, this is the only available port.
# aux_port is only available for the GQ7 and is only needed when streaming RTCM corrections to the device from ROS, or if you want to publish NMEA sentences from this node
port :"/dev/ttyACM0"
aux_port :"/dev/ttyACM1"
baudrate :115200
baudrate :115200
debug :False
diagnostics :False
# If set to true, this will configure the requested baudrate on the device.
# Note that this will be set on both USB and serial, but will only actually affect the baudrate of a serial connection.
set_baud :False
# Frame IDs used in the different messages. By default these are set to arbitrary strings as not to interfere with other ROS services.
# For more information on common frame IDs, check out: https://www.ros.org/reps/rep-0105.html
#
# filter_frame_id and filter_child_frame_id are specifically useful as the node will also publish a transform to the /tf topic
# that contains the transform between these two frames. Many ROS tools such as RViz will use the /tf topic to display things like robot position.
imu_frame_id :"gq7_link"
gnss1_frame_id :"gnss1_link"
gnss2_frame_id :"gnss2_link"
filter_frame_id :"map"
filter_child_frame_id :"sensor"
nmea_frame_id :"earth"
# This will cause the node to convert any NED measurements to ENU
# Waits for a configurable amount of time until the device exists
# This will also cause the node to convert any vehicle frame measurements to the ROS definition of a vehicle frame
# If poll_max_tries is set to -1 we will poll forever until the device exists
poll_port :False
poll_rate_hz :1.0
poll_max_tries :60
# Number of times to attempt to reconnect to the device if it disconnects while running
# If configure_after_reconnect is true, we will also reconfigure the device after we reconnect
# NOTE: It is strongly recommended to configure after reconnect unless device_setup is set to false
# as the device will likely initialize in a different state otherwise
reconnect_attempts :5
configure_after_reconnect :True
# Controls if the driver outputs data with-respect-to ENU frame
# false - position, velocity, and orientation are WRT the NED frame (native device frame)
# true - position, velocity, and orientation are WRT the ENU frame
use_enu_frame :True
use_enu_frame :True
# Configure some frame IDs
# Controls if the driver-defined setup is sent to the device
frame_id :'gq7_link'# Frame ID of all of the filter messages. Represents the location of the CV7-INS in the tf tree
# false - The driver will ignore the settings below and use the device's current settings
map_frame_id :"map"# Frame ID of the local tangent plane.
# true - Overwrite the current device settings with those listed below
earth_frame_id :"earth"# Frame ID of the global frame
device_setup :True
gnss1_frame_id :"gq7_gnss_1_antenna_link"
gnss2_frame_id :"gq7_gnss_2_antenna_link"
# Controls if the driver-defined settings are saved
odometer_frame_id :"gq7_odometer_link"
# false - Do not save the settings
target_frame_id :"base_link"# Frame ID that we will publish a transform to.
# true - Save the settings in the device's non-volatile memory
save_settings :True
# 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
# Controls if the driver uses the device generated timestamp (if available) for timestamping messages
# false - Use PC received time for timestamping
# We will use relative transform mode, meaning that we will publish the following transforms from this node
# true - Use device generated timestamp
# earth_frame_id -> map_frame_id
use_device_timestamp :True
# map_frame_id -> target_frame_id
# This helps ROS standard tools consume and display position information produced by the device
# Controls if the driver uses ROS time for timestamping messages. Can be useful when running under simulation.
tf_mode:2
# NOTE: This can be used in conjunction with use_device_timestamp in which case, the device timestmap will be used for sensor_msgs/TimeReference messages, and ROS time will be used for all other messages
# false - Use PC received time for timestamping
# Enable the RTK dongle interface for communication with the 3DM-RTK.
# true - Use ROS time for timestamping all non sensor_msgs/TimeReference messages
# Note: Even if you do not have a 3DM-RTK connected to the aux port, this boolean can remain true
use_ros_time :True
rtk_dongle_enable :True
# Controls if the driver creates a raw binary file
# We will use base station relative position configuration for this example. This configuration does a couple things:
# false - Do not create the file
# We will setup a local tangent plane at the location of the RTK base station being used by the GQ7.
# true - Create the file
# 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.
# Notes: 1) The filename will have the following format -
# If you do not have that device, see https://wiki.ros.org/microstrain_inertial_driver/relative_position_configuration for more options.
# The speed at which the individual Filter publishers will publish at.
# If set to -1, will use filter_data_rate to determine the rate at which to stream and publish
# If set to 0, the stream will be turned off and the publisher will not be created
#
# Note: The parameters' "filter_odom_data_rate", "filter_imu_data_rate", "filter_relative_odom_data_rate" associated ROS messages share several MIP fields,
# so if more than one is set to stream, and they are set to stream at different rates, messages will be published on both topics, at the higher rate
# Note: The parameters' "filter_navsatfix_data_rate", and "filter_aiding_status_data_rate" associated ROS messages share several MIP fields,
# so if more than one is set to stream, and they are set to stream at different rates, messages will be published on both topics, at the higher rate
filter_status_data_rate :-1# Rate of nav/status topic
filter_heading_data_rate :-1# Rate of nav/heading topic
filter_heading_state_data_rate :-1# Rate of nav/heading_state topic
filter_navsatfix_data_rate :-1# Rate of nav/fix topic
filter_odom_data_rate :-1# Rate of nav/odom topic
filter_imu_data_rate :-1# Rate of nav/filtered_imu/data
filter_relative_odom_data_rate :-1# Rate of nav/relative_pos topic and the transform between filter_frame_id and filter_child_frame_id
# Note that this data rate will also control the rate at which the transform between "filter_frame_id" and "filter_child_frame_id" will be published at
filter_aiding_status_data_rate :-1# Rate of gnss1/aiding_status and gnss2/aiding_status topics
filter_antenna_offset_correction_data_rate :-1# Rate of gnss1/antenna_offset_corection and gnss2/antenna_offset_correction topics
filter_gnss_dual_antenna_data_rate :-1# Rate of nav/dual_antenna_status topic
filter_aiding_measurement_summary_data_rate :-1# Rate of nav/aiding_summary topic
# 2 - WGS84 Latitude, Longitude, height above ellipsoid position, NED velocity and attitude
filter_init_condition_src :0
filter_auto_heading_alignment_selector :0,1
filter_init_reference_frame :1
filter_init_position :[0.0,0.0,0.0]
filter_init_velocity :[0.0,0.0,0.0]
filter_init_attitude :[0.0,0.0,0.0]
# (GQ7 only) Relative Position Configuration
# Reference frame =
# 1 - Relative ECEF position
# 2 - Relative LLH position
#
# Source =
# 0 - Position will be reported relative to the base station. filter_relative_position_ref will be ignored
# 1 - Position will be reported relative to filter_relative_position_ref
#
# Reference position - Units provided by reference frame (ECEF - meters, LLH - deg, deg, meters)
# Note: prior to firmware version 1.0.06 this command will fail for non-positive heights. 1.0.06 fixes this)
filter_relative_position_config :True
filter_relative_position_frame :1
filter_relative_position_source :2
filter_relative_position_ref :[0.0,0.0,0.01]
# (GQ7 only) Speed Lever Arm Configuration
# Lever Arm - In vehicle reference frame (meters)
filter_speed_lever_arm :[0.0,0.0,0.0]
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.
# (GQ7 only) Wheeled Vehicle Constraint Control
# You should update for your setup appropriately
# Note: When enabled, the filter uses the assumption that velocity is constrained to the primary vehicle axis.
gpio_config :True
# By convention, the primary vehicle axis is the vehicle X-axis
filter_enable_wheeled_vehicle_constraint :False
# (GQ7 only) Vertical Gyro Constraint Control
# Note: When enabled and no valid GNSS measurements are available, the filter uses the accelerometers to track
# pitch and roll under the assumption that the sensor platform is not undergoing linear acceleration.
# This constraint is useful to maintain accurate pitch and roll during GNSS signal outages.
filter_enable_vertical_gyro_constraint :True
# (GQ7 only) GNSS Antenna Calibration Control
# Note: When enabled, the filter will enable lever arm error tracking, up to the maximum offset specified in meters.
filter_enable_gnss_antenna_cal :True
filter_gnss_antenna_cal_max_offset :0.1
# (GQ7/CV7 only) PPS Source
# PPS Source =
# 0 - Disabled
# 1 - Reciever 1 (default)
# 2 - Reciever 2
# 3 - GPIO (provided by external source if supported). Use the GPIO config above to further configure
# 4 - Generated from system oscillator
filter_pps_source :1
# (GQ7 only) SBAS options
sbas_enable:True
sbas_enable_ranging:False
sbas_enable_corrections:True
sbas_apply_integrity:False
# (GQ7 only) SBAS included PRNs
# Note: ROS2 can't handle empty arrays in a yml file, so uncomment this line and fill it in if you want to specify PRNs
#sbas_included_prns: []
# (GQ7 only) NMEA message format. If set to false, all NMEA message configuration will not have any affect
nmea_message_config:True
# Allow NMEA messages with the same talker IDs on different data sources (descriptor sets)
# In most cases, this should be set to False, as multiple messages of the same type with the same talker ID from a different descriptor set could cause confusion when parsing.
nmea_message_allow_duplicate_talker_ids:False
# NMEA messages in the sensor (IMU) descriptor set
# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz
# Note: In order to publish, 'publish_nmea' must also be set to True
imu_nmea_prkr_data_rate:500
# NMEA messages in the GNSS1 descriptor set
# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz
#
# Note: In order to publish, 'publish_nmea' must also be set to True
#
# Note: gnss1_nmea_talker_id can be any of the follwing numeric values:
# 1 - Sentences will start with GN
# 2 - Sentences will start with GP
# 3 - Sentences will start with GA
# 4 - Sentences will start with GL
# The purpose of the talker ID is to differentiate when the same message_id comes from different data sources (descriptor sets)
# The gnss1_nmea_talker_id will be applied to all NMEA messages from the GNSS1 descriptor set
gnss1_nmea_talker_id:1
gnss1_nmea_gga_data_rate:0
gnss1_nmea_gll_data_rate:0
gnss1_nmea_gsv_data_rate:0# Note that this message_id will not use the gnss1_talker_id since the talker ID will come from the actual constellation the message originates from
gnss1_nmea_rmc_data_rate:0
gnss1_nmea_vtg_data_rate:0
gnss1_nmea_hdt_data_rate:0
gnss1_nmea_zda_data_rate:0
gpio1_feature :3# ENCODER feature
# NMEA messages in the GNSS2 descriptor set
gpio1_behavior :1# ENCODER_A behavior
# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz
gpio1_pin_mode :0# NONE pin_mode
#
# Note: In order to publish, 'publish_nmea' must also be set to True
#
# Note: gnss2_nmea_talker_id can be any of the follwing numeric values:
# 1 - Sentences will start with GN
# 2 - Sentences will start with GP
# 3 - Sentences will start with GA
# 4 - Sentences will start with GL
# The purpose of the talker ID is to differentiate when the same message_id comes from different data sources (descriptor sets)
# The gnss2_nmea_talker_id will be applied to all NMEA messages from the GNSS2 descriptor set
gnss2_nmea_talker_id:2
gnss2_nmea_gga_data_rate:0
gnss2_nmea_gll_data_rate:0
gnss2_nmea_gsv_data_rate:0# Note that this message_id will not use the gnss1_talker_id since the talker ID will come from the actual constellation the message originates from
gnss2_nmea_rmc_data_rate:0
gnss2_nmea_vtg_data_rate:0
gnss2_nmea_hdt_data_rate:0
gnss2_nmea_zda_data_rate:0
gpio2_feature :3# ENCODER feature
# NMEA messages in the filter descriptor set
gpio2_behavior :2# ENCODER_B behavior
# In order to enable a message, set nmea_message_config to true, and then change the 'data_rate' of the sentences you want to the desired rate in hertz
gpio2_pin_mode :0# NONE pin_mode
#
# Note: In order to publish, 'publish_nmea' must also be set to True
#
# Note: filter_nmea_talker_id can be any of the follwing numeric values:
# 1 - Sentences will start with GN
# 2 - Sentences will start with GP
# 3 - Sentences will start with GA
# 4 - Sentences will start with GL
# The purpose of the talker ID is to differentiate when the same message_id comes from different data sources (descriptor sets)
# The filter_nmea_talker_id will be applied to all NMEA messages from the filter descriptor set
filter_nmea_talker_id:3
filter_nmea_gga_data_rate:0
filter_nmea_gll_data_rate:0
filter_nmea_rmc_data_rate:0
filter_nmea_hdt_data_rate:0
filter_nmea_prka_data_rate:0# Note that this message_id will not have any talker ID on it since it is proprietary and can only come from the filter descriptor set