Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

How to reduce the output #102

Open
shushu-nantong opened this issue Jan 28, 2021 · 4 comments
Open

How to reduce the output #102

shushu-nantong opened this issue Jan 28, 2021 · 4 comments

Comments

@shushu-nantong
Copy link

We use serial port to record "INSPVAA" and "CORRIMUDATAA"。
The launch file is:
image

The corresponding result is:
image

in which GPGGAA, BESTPOSA, BESTVELA, GPGGA, GPRMC, INSCOVA, INSPVAXA, TIMEA are not needed.

How can we remove all the other signals and log only the ones we want?

Thank you.

@pjreed
Copy link
Contributor

pjreed commented Jan 28, 2021

This driver is intended to be used for publishing ROS messages; if publish_imu_messages is true, then it will always configure the device to produce CORRIMUDATA, INSCOV, INSPVA, INSPVAX, and INSSTDEV logs because it needs all of those in order to generate sensor_msgs/Imu ROS messages. Your device will not always produce all of those, though, because some are exclusive to OEM6 devices and others are exclusive to OEM7s.

If the driver is having problems because the serial connection doesn't have enough bandwidth to log all of those messages at the full rate, I would very strongly recommend setting the use_binary_messages confim param to true; it's a known issue that typical serial connections just don't provide enough bandwidth for logging IMU data in ASCII mode. You could also try lowering the imu_rate parameter if you don't need frequent updates.

If you really need to log some of those messages in ASCII mode and you don't care about others, you could edit the source code near novatel_gps_driver/src/nodelets/novatel_gps_nodelet.cpp:483 to change which logs it requests when publish_imu_messages is true, but keep in mind that the driver may not be able to publish sensor_msgs/Imu messages in that case.

Similarly, it also always configures the device to log BESTPOS and BESTVEL logs because those are necessary to produce gps_common/GPSFix messages. Those messages are always published because the driver was originally intended only for producing GPS data, so there would be no point in disabling that, but if it would be useful for you to only publish IMU data and not GPS data, then it might make sense to also make that optional. GPGGA and TIME are logged mostly for backwards-compatibility purposes -- they used to be used when producing GPSFixes, and while they're not any more, removing them by default would break any system that still expects them to be available. That behavior was changed long enough ago that at this point it would make sense to at least add parameters to disable them.

For a temporary solution, similar to what I suggested above, you could edit novatel_gps_driver/src/nodelets/novatel_gps_nodelet.cpp:436 to disable logs that are always enabled. This will, of course, cause the driver to not publish gps_common/GPSFix messages, and it will probably cause some of the diagnostics to indicate errors.

@shushu-nantong
Copy link
Author

Very understandable explanations. We will test your suggestions and update the result. Thank you~

@shushu-nantong
Copy link
Author

This driver is intended to be used for publishing ROS messages; if publish_imu_messages is true, then it will always configure the device to produce CORRIMUDATA, INSCOV, INSPVA, INSPVAX, and INSSTDEV logs because it needs all of those in order to generate sensor_msgs/Imu ROS messages.

image
Since it has already generated rostopics /inspva (novatel_gps_msgs/Inspva) and /corrimudata(novatel_gps_msgs/NovatelCorrectedImuData), why rostopic /imu(sensor_msgs/Imu) is still needed? Or what is the specificity of the /imu topic?

@pjreed
Copy link
Contributor

pjreed commented Jan 29, 2021

novatel_gps_msgs/Inspva and novatel_gps_msgs/NovatelCorrectedImuData messages are specific to Novatel devices and are only produced by this driver; sensor_msgs/Imu is a generic IMU message that is designed to be produced by any sensor that provides IMU data, and most ROS packages that are designed to work with any IMU, such as the robot_localization package, expect that message.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants