The ADMA uses a combination of GNSS-Receiver and an IMU that consists of three accelerometers and three gyroscopes. Due to this, different ROS topics are getting filled with sensor, GNSS and combined measurement data as shown in the following list:
Topic | Description |
---|---|
/adma/data_scaled | ADMAnet v3.3.x |
/adma/status | ADMAnet Status / Error / Warning v3.3.x |
/adma/heading | std_msgs::Float64 |
/adma/velocity | std_msgs::Float64 |
/adma/fix | sensor_msgs::Navsatfix |
/adma/imu | sensor_msgs::imu |
/adma/odometry | nav_msgs::Odometry |
/adma/data_raw | Raw UDP Data Stream |
/adma/data_scaled Message
This topic is a new ROS topic introduced by the ADMA ROS Driver. The definition is derived by the ADMAnet data format specification. (See article ADMAnet – List of data packets v3.3.x)
/adma/status
This topic is a new ROS topic introudced by the ADMA ROS Driver. It contains all status, warning and error information.
/adma/heading
Standard ROS Topic Heading.
ROS topic field | ADMA data channel |
---|---|
Heading | INS_Yaw |
/adma/velocity
Standard ROS topic velocity.
ROS topic field | ADMA data channel |
---|---|
Velocity | sqrt ( INS_Vel_Hor_X_POI1 ^2 + INS_Vel_Hor_Y_POI1 ^2 ) |
/adma/fix
Standard ROS topic fix.
ROS topic field | ADMA data channel |
---|---|
Status | Status_GNSS_Mode |
Altitude | INS_Height |
Latitude | INS_Lat_Abs |
Longitude | INS_Long_Abs |
Position_covariance[0] | INS_Stddev_Lat^2 |
Position_covariance[4] | INS_Stddev_Long^2 |
Position_covariance[8] | INS_Stddev_Height^2 |
Covariance_Type | COVARIANCE_TYPE_DIAGONAL_KNOWN |
/adma/imu
Standard ROS topic imu.
ROS topic field | ADMA data channel |
---|---|
Linear_acceleration.x | Acc_Body_HR_X * 9.81 m/s^2 |
Linear_acceleration.y | Acc_Body_HR_Y * 9.81 m/s^2 |
Linear_acceleration.z | Acc_Body_HR_Z * 9.81 m/s^2 |
Angular_velocity.x | Rate_Body_HR_X * π / 180 |
Angular_velocity.y | Rate_Body_HR_Y * π / 180 |
Angular_velocity.z | Rate_Body_HR_Z * π / 180 |
Roll_rad | INS_Roll * π / 180 |
Pitch_rad | INS_Pitch * π / 180 |
Yaw_rad | INS_Yaw * π / 180 |
Orientation_Covariance[0] | (INS_Stddev_Roll * π / 180) ^2 |
Orientation_Covariance[4] | (INS_Stddev_Pitch * π / 180) ^2 |
Orientation_Covariance[8] | (INS_Stddev_Yaw * π / 180) ^2 |
// ADMA does not provide covariance for linear acceleration and angular velocity.
// These values need to be measured at standstill each ADMA model.
imu_ros_msg.angular_velocity_covariance[0] = -1;
imu_ros_msg.linear_acceleration_covariance[0] = -1;
/adma/odometry
Standard ROS topic odometry.
ROS topic field | ADMA data channel |
---|---|
Pose position x | INS_Pos_Rel_X |
Pose position y | INS_Pos_Rel_Y |
Pose position z | INS_Height |
Pose orientation x | INS_Roll |
Pose orientation y | INS_Pitch |
Pose orientation z | INS_Yaw |
Position_covariance[0] | INS_Stddev_Lat^2 |
Position_covariance[4] | INS_Stddev_Long^2 |
Position_covariance[8] | INS_Stddev_Height^2 |
Linear twist x | INS_Vel_Hor_X |
Linear twist y | INS_Vel_Hor_Y |
Linear twist z | INS_Vel_Hor_Z |
Angular twist x | Rate_Body_X |
Angular twist y | Rate_Body_Y |
Angular twist z | Rate_Body_Z |
Velocity_covariance[0] | INS_Stddev_Vel_X^2 |
Velocity_covariance[4] | INS_Stddev_Vel_Y^2 |
Velocity_covariance[8] | INS_Stddev_Vel_Z^2 |