-
Notifications
You must be signed in to change notification settings - Fork 77
Publishers
The main use of the ROS driver is to convert device data into ROS messages. See below for a mapping between the ROS topics and messages to the MIP messages that populate them
The following topics contain standard ROS messages often used by other nodes. Sensor data is often massaged or converted to be fit into what the ROS standards dictate.
-
/imu/data_raw sensor_msgs/Imu
-
angular_velocity
-> Scaled Gyro(0x80,0x05) -
linear_acceleration
-> Scaled Accel (0x80,0x04)- The x,y,z values are reported by the device in Gs, but are converted to m/s^2 for ROS.
-
-
/imu/data sensor_msgs/Imu
-
orientation
-> Complementary Filter Quaternion (0x80, 0x0A) -
angular_velocity
-> Delta Theta (0x80, 0x07)- This measurement is the delta theta, so it is divided by the time since it was last sampled to get angular velocity
-
linear_acceleration
-> Delta Velocity(0x80, 0x08)- The x,y,z values reported by the device are in Gs, but are converted to m/s^2 for ROS.
- This measurement is the delta velocity, so it is divided by the time since it was last sampled to get linear acceleration.
-
-
/imu/mag sensor_msgs/MagneticField
-
magnetic_field
-> Scaled Mag (0x80, 0x06)
-
-
/imu/pressure sensor_msgs/FluidPressure
-
fluid_pressure
-> Scaled Pressure (0x80, 0x17)- The device reports data in mBar, but the data is converted into Pascals for ROS.
-
-
/imu/wheel_speed geometry_msgs/TwistWithCovarianceStamped
-
twist.twist.linear.x
-> Odometer Data (0x80, 0x40) -
twist.covariance[0]
-> Odometer Data (0x80, 0x40)
-
-
/gnss_1/llh_position sensor_msgs/NavSatFix -> GNSS LLH Position (0x91, 0x03)
-
/gnss_1/velocity geometry_msgs/TwistWithCovarianceStamped -> GNSS NED Velocity (0x91, 0x05)
-
/gnss_1/velocity_ecef geometry_msgs/TwistWithCovarianceStamped -> GNSS ECEF Velocity (0x91, 0x06)
-
/gnss_1/odometry_earth nav_msgs/Odometry
-
pose
-> GNSS ECEF Position (0x91, 0x04) -
twist
-> GNSS ECEF Velocity (0x91, 0x06)
-
-
/gnss_1/time sensor_msgs/TimeReference -> GPS Timestamp (0x91, 0xD3)
-
/gnss_2/llh_position sensor_msgs/NavSatFix -> GNSS LLH Position (0x92, 0x03)
-
/gnss_2/velocity geometry_msgs/TwistWithCovarianceStamped -> GNSS NED Velocity (0x92, 0x05)
-
/gnss_2/velocity_ecef geometry_msgs/TwistWithCovarianceStamped -> GNSS ECEF Velocity (0x92, 0x06)
-
/gnss_2/odometry_earth nav_msgs/Odometry
-
pose
-> GNSS ECEF Position (0x92, 0x04) -
twist
-> GNSS ECEF Velocity (0x92, 0x06)
-
-
/gnss_2/time sensor_msgs/TimeReference -> GPS Timestamp (0x92, 0xD3)
-
/ekf/imu/data sensor_msgs/Imu
-
orientation
-> Attitude Quaternion (0x82, 0x03) -
orientation_covariance
-> Euler Angles Uncertainty (0x82, 0x0A) -
angular_velocity
-> Compensated Angular Rate (0x82, 0x0E) -
linear_acceleration
-> Compensated Acceleration (0x82, 0x1C)
-
-
/ekf/llh_position sensor_msgs/NavSatFix
-
status
-> GNSS Position Aiding Status (0x82, 0x43) -
latitude
-> LLH Position (0x82, 0x01) -
longitude
-> LLH Position (0x82, 0x01) -
altitude
-> LLH Position (0x82, 0x01) -
position_covariance
-> LLH Position Uncertainty (0x82, 0x08)
-
-
/ekf/velocity geometry_msgs/TwistWithCovarianceStamped
-
twist.covariance
-> NED Velocity Uncertainty (0x82, 0x09) -
twist.twist.linear
-> NED Velocity (0x82, 0x02) -
twist.twist.angular
-> Comp Angular Rate (0x82, 0x0E)
-
-
/ekf/velocity_ecef geometry_msgs/TwistWithCovarianceStamped
-
twist.covariance
-> ECEF Velocity Unvertainty (0x82, 0x37) -
twist.twist.linear
-> ECEF Velocity (0x82, 0x41) -
twist.twist.angular
-> Comp Angular Rate (0x82, 0x0E)
-
-
/ekf/odometry_earth nav_msgs/Odometry
-
pose.covariance
-> ECEF Position Uncertainty (0x82, 0x36) and Euler Angles Uncertainty (0x82, 0x0A) -
pose.pose.position
-> ECEF Position (0x82, 0x40) -
pose.pose.orientation
-> Attitude Quaternion (0x82, 0x03) -
twist.covariance
-> ECEF Velocity Unvertainty (0x82, 0x37) -
twist.twist.linear
-> ECEF Velocity (0x82, 0x41) -
twist.twist.angular
-> Comp Angular Rate (0x82, 0x0E)
-
-
/ekf/odometry_map nav_msgs/Odometry
-
pose.covariance
-> LLH Position Uncertainty (0x82, 0x08) and Euler Angles Uncertainty (0x82, 0x0A) -
pose.pose.position
-> ECEF Position (0x82, 0x40)- The ECEF position is converted to a local position relative to the relative position configuration before populating this message
-
pose.pose.orientation
Attitude Quaternion (0x82, 0x03) -
twist.covariance
-> NED Velocity Uncertainty (0x82, 0x09) -
twist.twist.linear
-> NED Velocity (0x82, 0x02) -
twist.twist.angular
-> Comp Angular Rate (0x82, 0x0E)
-
-
/ekf/dual_antenna_heading ->geometry_msgs/PoseWithCovarianceStamped
-
pose.pose.orientation
-> GNSS Dual Antenna Status (0x82, 0x49)- Only the rotation about the Z axis will be populated in the orientation.
-
The following topics contain messages that are exact copies of their MIP counterparts. The topic format is
/mip/<descriptor_set_name>/<field_descriptor_name>
For more information on what descriptor_set_name
and field_descriptor_name
mean, see the MIP Protocol
page.
See the message definitions for links to their MIP fields as well as field documentation
- /mip/sensor/temperature_statistics microstrain_inertial_msgs/MipSensorTemperatureStatistics
- /mip/sensor/overrange_status microstrain_inertial_msgs/MipSensorOverrangeStatus
- /mip/gnss_1/fix_info microstrain_inertial_msgs/MipGnssFixInfo
- /mip/gnss_1/sbas_info microstrain_inertial_msgs/MipGnssSbasInfo
- /mip/gnss_1/rf_error_detection microstrain_inertial_msgs/MipGnssRfErrorDetection
- /mip/gnss_2/fix_info microstrain_inertial_msgs/MipGnssFixInfo
- /mip/gnss_2/sbas_info microstrain_inertial_msgs/MipGnssSbasInfo
- /mip/gnss_2/rf_error_detection microstrain_inertial_msgs/MipGnssRfErrorDetection
- /mip/gnss_corrections/rtk_corrections_status microstrain_inertial_msgs/MipGnssCorrectionsRtkCorrectionsStatus
- /mip/ekf/status microstrain_inertial_msgs/MipFilterStatus
- /mip/ekf/gnss_position_aiding_status microstrain_inertial_msgs/MipFilterGnssPositionAidingStatus
- /mip/ekf/multi_antenna_offset_correction microstrain_inertial_msgs/MipFilterMultiAntennaOffsetCorrection
- /mip/ekf/gnss_dual_antenna_status microstrain_inertial_msgs/MipFilterGnssDualAntennaStatus
- /mip/ekf/aiding_measurement_summary microstrain_inertial_msgs/MipFilterAidingMeasurementSummary
- /mip/system/built_in_test microstrain_inertial_msgs/MipSystemBuiltInTest
The following topics do not fall into any of the above categories and are likely addons to the device not specifically from the MIP protocol
-
/ekf/status microstrain_inertial_msgs/HumanReadableStatus
- Human readable status of the device. This message will contain strings that should be easily readable, but SHOULD NOT be used in a production application
-
/nmea nmea_msgs/Sentence
-
GGA NMEA sentences may be published from the aux port of a GQ7 if it is connected and the following configuration is set:
aux_port: '/dev/ttyACM1' # The serial port that the aux port is connected on ntrip_interface_enable: True # Enable the sending of NMEA messages
-
Several types of NMEA sentences may be published from the main port of the GQ7 if this section of config is configured to stream NMEA.
-