Closed Aussie25 closed 2 years ago
Hello,
Unfortunately, the driver does not have this as an option. It is easy to do if you want to branch the code and make a few edits. You could make one or more edits to microstrain_3dm.cpp:
Hope that helps!
Thank for the response. To make the the filter rate dependent to the channel name is it done like this for example "supportedChannels.push_back(mscl::MipChannel(CH_FIELD_ESTFILTER_FILTER_STATUS, 10));"
That is correct... as long as you also remove CH_FIELD_ESTFILTER_FILTER_STATUS from the supported descriptors list above this, otherwise you would get 2 copies of the data, one at the filter rate and one at 10 hz.
Thanks you very much, I will try it out.
Hi Nathan,
Seems like i have issue building the code after making the changes.
This were the changes made,
Got this errors while building: error: ‘CH_FIELD_ESTFILTER_FILTER_STATUS’ was not declared in this scope supportedChannels.push_back(mscl::MipChannel(CH_FIELD_ESTFILTER_FILTER_STATUS, 10));
Thanks for your assistance.
Hi @Aussie25
If you change the line:
supportedChannels.push_back(mscl::MipChannel(CH_FIELD_ESTFILTER_FILTER_STATUS, 10));
to:
supportedChannels.push_back(mscl::MipChannel(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS, mscl::SampleRate::Hertz(10)));
It should build.
However, this would result in adding filter status to the channel list multiple times. If I understand your usecase correctly, you could replace the code snippet you screenshoted with the following code to add filter status only once at your deisred rate of 10hz:
mscl::MipChannels supportedChannels;
for(mscl::MipTypes::ChannelField channel : m_inertial_device->features().supportedChannelFields(mscl::MipTypes::DataClass::CLASS_ESTFILTER))
{
if(std::find(navChannels.begin(), navChannels.end(), channel) != navChannels.end())
{
//supportedChannels.push_back(mscl::MipChannel(channel, filter_rate));
if (channel == mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS)
{
supportedChannels.push_back(mscl::MipChannel(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS, mscl::SampleRate::Hertz(10)));
}
}
}
Hey,
The code provided work to publish the filter statues message at 10hz. But when i enable the other filter messages, it will overwrite of the filter statues frequency.
`
ROS_INFO("Setting Filter data to stream at %d hz", m_filter_data_rate);
mscl::MipTypes::MipChannelFields navChannels{
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_GPS_TIMESTAMP,
//mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_LLH_POS,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_NED_VELOCITY,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ORIENT_QUATERNION,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_LLH_UNCERT,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_NED_UNCERT,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ATT_UNCERT_QUAT,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ANGULAR_RATE,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ATT_UNCERT_EULER,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_COMPENSATED_ACCEL,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ORIENT_EULER,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_HEADING_UPDATE_SOURCE,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_NED_RELATIVE_POS};
if(filter_enable_gnss_pos_vel_aiding)
navChannels.push_back(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_POSITION_AIDING_STATUS);
if(filter_enable_gnss_heading_aiding)
navChannels.push_back(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_GNSS_DUAL_ANTENNA_STATUS);
mscl::MipChannels supportedChannels;
for(mscl::MipTypes::ChannelField channel : m_inertial_device->features().supportedChannelFields(mscl::MipTypes::DataClass::CLASS_ESTFILTER))
{
if(std::find(navChannels.begin(), navChannels.end(), channel) != navChannels.end())
{
supportedChannels.push_back(mscl::MipChannel(channel, filter_rate));
if (channel == mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS)
{
supportedChannels.push_back(mscl::MipChannel(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS, mscl::SampleRate::Hertz(10)));
}
}
}`
I am trying reduce frequency of statues messages, so i could receive the filtered IMU data at 500hz smoothly. The gnss data rate is set to 2hz, but the gnss aiding statues and dual antenna statues follows the filter data rate.
Thanks for your help!
I think I understand. The following code snippet would reduce the rate of Filter Status, Position Aiding Status, and Dual Antenna Status to 10hz
, while allowing the rest of the data to go through at the specified rate, which I assume you have set to 500hz
:
ROS_INFO("Setting Filter data to stream at %d hz", m_filter_data_rate);
mscl::MipTypes::MipChannelFields navChannels{
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_GPS_TIMESTAMP,
//mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_LLH_POS,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_NED_VELOCITY,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ORIENT_QUATERNION,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_LLH_UNCERT,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_NED_UNCERT,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ATT_UNCERT_QUAT,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ANGULAR_RATE,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ATT_UNCERT_EULER,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_COMPENSATED_ACCEL,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_ESTIMATED_ORIENT_EULER,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_HEADING_UPDATE_SOURCE,
mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_NED_RELATIVE_POS};
if(filter_enable_gnss_pos_vel_aiding)
navChannels.push_back(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_POSITION_AIDING_STATUS);
if(filter_enable_gnss_heading_aiding)
navChannels.push_back(mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_GNSS_DUAL_ANTENNA_STATUS);
mscl::MipChannels supportedChannels;
for(mscl::MipTypes::ChannelField channel : m_inertial_device->features().supportedChannelFields(mscl::MipTypes::DataClass::CLASS_ESTFILTER))
{
if(std::find(navChannels.begin(), navChannels.end(), channel) != navChannels.end())
{
// Reduce the rate of Filter Status to 10hz
if (channel == mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_FILTER_STATUS)
{
supportedChannels.push_back(mscl::MipChannel(channel, mscl::SampleRate::Hertz(10)));
}
// Reduce the rate of Dual Antenna Status to 10hz
else if (channel == mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_GNSS_DUAL_ANTENNA_STATUS)
{
supportedChannels.push_back(mscl::MipChannel(channel, mscl::SampleRate::Hertz(10)));
}
// Reduce the rate of Position Aiding Status to 10hz
else if (channel == mscl::MipTypes::ChannelField::CH_FIELD_ESTFILTER_POSITION_AIDING_STATUS)
{
supportedChannels.push_back(mscl::MipChannel(channel, mscl::SampleRate::Hertz(10)));
}
// Set all other filter data to stream at the rate specified in the launch file
else
{
supportedChannels.push_back(mscl::MipChannel(channel, filter_rate));
}
}
}
If there is more data you want to reduce the rate of, you could add another else if
block that checks the channel
against the mscl::MipTypes::ChannelField::*
that you want to reduce the rate of.
Hey, Tried out the above code snippet but the topics are not publishing at 10hz but instead of 1000hz. Whereby the filter data rate is set to 500hz.
Hi @Aussie25
I am not sure I understand what you are saying. Are you saying that you are seeing filter data at 1000hz despite setting the filter_data_rate
argument in your launch file to 500?
How are you measuring the data rates? I measured the rates with the command rostopic hz /gq7/nav/status /gq7/nav/dual_antenna_status /gq7/nav/filtered_imu/data /gq7/nav/heading /gq7/nav/heading_state /gq7/nav/odom
I have implemented the changes we spoke about in the following fork, does this looks similar to your setup?
Hi Robbie,
Yup, my set up is identical as your fork version. I even tried running your fork set up, leads to the same issues.
Despite setting the filter_data_rate
as 500 in the launch file, the filter data rate is being publish at 1000hz. I am measuring the topic frequency with rostopic hz
too.
My terminal output after launch
PARAMETERS
* /gx5/ros_mscl_node/baudrate: 921600
* /gx5/ros_mscl_node/device_setup: True
* /gx5/ros_mscl_node/filter_adaptive_level: 2
* /gx5/ros_mscl_node/filter_adaptive_time_limit_ms: 15000
* /gx5/ros_mscl_node/filter_angular_zupt: True
* /gx5/ros_mscl_node/filter_angular_zupt_topic: /moving_ang
* /gx5/ros_mscl_node/filter_auto_heading_alignment_selector: 1
* /gx5/ros_mscl_node/filter_auto_init: True
* /gx5/ros_mscl_node/filter_data_rate: 500
* /gx5/ros_mscl_node/filter_declination: 0.23
* /gx5/ros_mscl_node/filter_declination_source: 2
* /gx5/ros_mscl_node/filter_dynamics_mode: 1
* /gx5/ros_mscl_node/filter_enable_altimeter_aiding: False
* /gx5/ros_mscl_node/filter_enable_external_gps_time_update: False
* /gx5/ros_mscl_node/filter_enable_external_heading_aiding: False
* /gx5/ros_mscl_node/filter_enable_gnss_antenna_cal: False
* /gx5/ros_mscl_node/filter_enable_gnss_heading_aiding: True
* /gx5/ros_mscl_node/filter_enable_gnss_pos_vel_aiding: True
* /gx5/ros_mscl_node/filter_enable_magnetometer_aiding: False
* /gx5/ros_mscl_node/filter_enable_odometer_aiding: False
* /gx5/ros_mscl_node/filter_enable_vertical_gyro_constraint: False
* /gx5/ros_mscl_node/filter_enable_wheeled_vehicle_constraint: False
* /gx5/ros_mscl_node/filter_external_gps_time_topic: /external_gps_time
* /gx5/ros_mscl_node/filter_frame_id: sensor_wgs84
* /gx5/ros_mscl_node/filter_gnss_antenna_cal_max_offset: 0.1
* /gx5/ros_mscl_node/filter_heading_source: 1
* /gx5/ros_mscl_node/filter_init_attitude: [0.0, 0.0, 0.0]
* /gx5/ros_mscl_node/filter_init_condition_src: 0
* /gx5/ros_mscl_node/filter_init_position: [0.0, 0.0, 0.0]
* /gx5/ros_mscl_node/filter_init_reference_frame: 2
* /gx5/ros_mscl_node/filter_init_velocity: [0.0, 0.0, 0.0]
* /gx5/ros_mscl_node/filter_pps_source: 1
* /gx5/ros_mscl_node/filter_relative_position_frame: 2
* /gx5/ros_mscl_node/filter_relative_position_ref: [0, 0, 0.01]
* /gx5/ros_mscl_node/filter_reset_after_config: True
* /gx5/ros_mscl_node/filter_sensor2vehicle_frame_selector: 1
* /gx5/ros_mscl_node/filter_sensor2vehicle_frame_transformation_euler: [0.0, 0.0, 0.0]
* /gx5/ros_mscl_node/filter_sensor2vehicle_frame_transformation_matrix: [1.0, 0.0, 0.0, 0...
* /gx5/ros_mscl_node/filter_sensor2vehicle_frame_transformation_quaternion: [0.0, 0.0, 0.0, 1.0]
* /gx5/ros_mscl_node/filter_speed_lever_arm: [0.0, 0.0, 0.0]
* /gx5/ros_mscl_node/filter_velocity_zupt: True
* /gx5/ros_mscl_node/filter_velocity_zupt_topic: /moving_vel
* /gx5/ros_mscl_node/gnss1_antenna_offset: [0.0, -0.7, -1.0]
* /gx5/ros_mscl_node/gnss1_data_rate: 2
* /gx5/ros_mscl_node/gnss1_frame_id: gnss1_antenna_wgs84
* /gx5/ros_mscl_node/gnss2_antenna_offset: [0.0, 0.7, -1.0]
* /gx5/ros_mscl_node/gnss2_data_rate: 2
* /gx5/ros_mscl_node/gnss2_frame_id: gnss2_antenna_wgs84
* /gx5/ros_mscl_node/gpio1_behavior: 0
* /gx5/ros_mscl_node/gpio1_feature: 0
* /gx5/ros_mscl_node/gpio1_pin_mode: 0
* /gx5/ros_mscl_node/gpio2_behavior: 0
* /gx5/ros_mscl_node/gpio2_feature: 0
* /gx5/ros_mscl_node/gpio2_pin_mode: 0
* /gx5/ros_mscl_node/gpio3_behavior: 0
* /gx5/ros_mscl_node/gpio3_feature: 0
* /gx5/ros_mscl_node/gpio3_pin_mode: 0
* /gx5/ros_mscl_node/gpio4_behavior: 0
* /gx5/ros_mscl_node/gpio4_feature: 0
* /gx5/ros_mscl_node/gpio4_pin_mode: 0
* /gx5/ros_mscl_node/gpio_config: False
* /gx5/ros_mscl_node/gps_leap_seconds: 18
* /gx5/ros_mscl_node/imu_angular_cov: [0.01, 0, 0, 0, 0...
* /gx5/ros_mscl_node/imu_data_rate: 100
* /gx5/ros_mscl_node/imu_frame_id: sensor
* /gx5/ros_mscl_node/imu_linear_cov: [0.01, 0, 0, 0, 0...
* /gx5/ros_mscl_node/imu_orientation_cov: [0.01, 0, 0, 0, 0...
* /gx5/ros_mscl_node/port: /dev/ttyACM0
* /gx5/ros_mscl_node/publish_filter: True
* /gx5/ros_mscl_node/publish_gnss1: True
* /gx5/ros_mscl_node/publish_gnss2: True
* /gx5/ros_mscl_node/publish_gps_corr: False
* /gx5/ros_mscl_node/publish_imu: True
* /gx5/ros_mscl_node/publish_relative_position: False
* /gx5/ros_mscl_node/raw_file_directory: /home/your_name
* /gx5/ros_mscl_node/raw_file_enable: False
* /gx5/ros_mscl_node/raw_file_include_support_data: False
* /gx5/ros_mscl_node/rtk_dongle_enable: False
* /gx5/ros_mscl_node/save_settings: False
* /gx5/ros_mscl_node/use_device_timestamp: False
* /gx5/ros_mscl_node/use_enu_frame: False
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/expected: ['ros_mscl_node: ...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/imu/expected: ['ros_mscl_node: ...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/imu/path: imu
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/imu/remove_prefix: ros_mscl_node
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/imu/timeout: 5.0
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/imu/type: diagnostic_aggreg...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/packet/expected: ['ros_mscl_node: ...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/packet/path: packet
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/packet/remove_prefix: ros_mscl_node
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/packet/timeout: 5.0
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/packet/type: diagnostic_aggreg...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/path: general
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/port/expected: ['ros_mscl_node: ...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/port/path: port
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/port/remove_prefix: ros_mscl_node
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/port/timeout: 5.0
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/port/type: diagnostic_aggreg...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/remove_prefix: ros_mscl_node
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/timeout: 5.0
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/analyzers/general/type: diagnostic_aggreg...
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/path: ros_mscl_node
* /imu_diagnostic_aggregator/analyzers/ros_mscl_node/type: diagnostic_aggreg...
* /rosdistro: melodic
* /rosversion: 1.14.12
NODES
/
imu_diagnostic_aggregator (diagnostic_aggregator/aggregator_node)
/gx5/
ros_mscl_node (ros_mscl/ros_mscl_node)
ROS_MASTER_URI=http://localhost:11311
process[gx5/ros_mscl_node-1]: started with pid [18825]
process[imu_diagnostic_aggregator-2]: started with pid [18826]
[ INFO] [1635844135.287249504]: Using MSCL Version: 62.0.0
[ INFO] [1635844135.287993011]: Attempting to open serial port </dev/ttyACM0> at <921600>
[ INFO] [1635844135.309105523]: Model Name: 3DM-GQ7
[ INFO] [1635844135.309177075]: Serial Number: 6284.121575
[ INFO] [1635844135.326967016]: Setting to Idle: Stopping data streams and/or waking from sleep
[ INFO] [1635844135.332905431]: Setting IMU data to stream at 100 hz
[ INFO] [1635844135.344855496]: Setting Declination Source
[ INFO] [1635844135.363018643]: Setting GNSS1 data to stream at 2 hz
[ INFO] [1635844135.375044584]: Setting GNSS1 antenna offset to [0.000000, -0.700000, -1.000000]
[ INFO] [1635844135.393121108]: Setting GNSS2 data to stream at 2 hz
[ INFO] [1635844135.405107839]: Setting GNSS2 antenna offset to [0.000000, 0.700000, -1.000000]
[ INFO] [1635844135.423131216]: Setting Filter data to stream at 500 hz
[ INFO] [1635844135.435263544]: Note: The device does not support the vehicle dynamics mode command.
[ INFO] [1635844135.435535309]: Setting PPS source to 0X01
[ INFO] [1635844135.441705358]: Note: The device does not support the heading source command.
[ INFO] [1635844135.441802835]: Note: The device does not support the filter autoinitialization command.
[ INFO] [1635844135.441847959]: Setting autoadaptive options to: level = 2, time_limit = 15000
[ INFO] [1635844135.454949541]: Filter aiding set to: pos/vel = 1, gnss heading = 1, altimeter = 0, odometer = 0, magnetometer = 0, external heading = 0
[ INFO] [1635844135.507816185]: Note: The device does not support the relative position command.
[ INFO] [1635844135.513792624]: Setting wheeled vehicle contraint enable to 0
[ INFO] [1635844135.519757632]: Setting vertical gyro contraint enable to 0
[ INFO] [1635844135.531903633]: Setting GNSS antenna calibration to: enable = 0, max_offset = 0.100000
[ INFO] [1635844135.567905604]: Setting sensor2vehicle frame transformation with euler angles [0.000000, 0.000000, 0.000000]
[ INFO] [1635844135.573687113]: Resetting the filter after the configuration is complete.
[ INFO] [1635844135.587741737]: Publishing IMU data.
[ INFO] [1635844135.589273651]: Publishing Magnetometer data.
[ INFO] [1635844135.590697760]: Publishing GNSS1 data.
[ INFO] [1635844135.596626094]: Publishing GNSS2 data.
[ INFO] [1635844135.602476922]: Publishing Filter data.
[ INFO] [1635844135.628182496]: Setting spin rate to <1000>
[ INFO] [1635844135.631786413]: Starting Data Parsing
rostopic hz /gx5/nav/filtered_imu/data
subscribed to [/gx5/nav/filtered_imu/data]
average rate: 1007.002
min: 0.000s max: 0.011s std dev: 0.00192s window: 944
subscribed to [/gx5/nav/status]
subscribed to [/gx5/nav/dual_antenna_status]
subscribed to [/gx5/nav/filtered_imu/data]
subscribed to [/gx5/nav/heading]
subscribed to [/gx5/nav/heading_state]
subscribed to [/gx5/nav/odom]
topic rate min_delta max_delta std_dev window
====================================================================================
/gx5/nav/status 1.002e+03 6.914e-06 0.02996 0.001612 1041
/gx5/nav/dual_antenna_status 499.0 8.106e-06 0.03336 0.002508 1041
/gx5/nav/filtered_imu/data 996.1 5.007e-06 0.02928 0.002466 522
/gx5/nav/heading 1.026e+03 5.96e-06 0.01073 0.001365 522
/gx5/nav/heading_state 998.5 7.868e-06 0.01165 0.001366 1034
/gx5/nav/odom 999.8 5.007e-06 0.02884 0.003201 1034
Thank you.
Thank you very much for the information. I see the same behavior that you posted on the master
branch. Were your tests done on master, or on the "example/different_rates" branch I linked to?
As a sanity check could you check that no other ros_mscl
nodes are running by checking the output of rosnode list
and then try running the following commands?
In one terminal:
$ git clone -b "example/different_rates" https://github.com/robbiefish/microstrain_inertial.git ~/microstrain_test_ws/src/microstrain_inertial
$ cd ~/microstrain_test_ws
$ source /opt/ros/melodic/setup.bash
$ catkin_make
$ source devel/setup.bash
$ roslaunch ros_mscl microstrain.launch
In a second terminal
$ source ~/microstrain_test_ws/devel/setup.bash
$ rostopic hz /gq7/nav/status /gq7/nav/dual_antenna_status /gq7/nav/filtered_imu/data /gq7/nav/heading /gq7/nav/heading_state /gq7/nav/odom
Closing this issue due to inactivity. Please reopen if more help is required
Hi, when I try run the gq7 at 500hz for both imu and filter data rate. The messages received are not consistent. The baudrate is set to 921600.
Is It possible to reduce the data rate of the topics like gq7/gnss1/aiding_statues, gq7/gnss2/aiding_statues , gq7/mag , gq7/nav/dual_antenna statues and gq7/nav/statues.