Technical Support Center

ROS – Available ROS topics


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:

TopicDescription
/adma/data_scaledADMAnet v3.3.x
/adma/statusADMAnet Status / Error / Warning v3.3.x
/adma/headingstd_msgs::Float64
/adma/velocitystd_msgs::Float64
/adma/fixsensor_msgs::Navsatfix
/adma/imusensor_msgs::imu
/adma/odometrynav_msgs::Odometry
/adma/data_rawRaw 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 fieldADMA data channel
HeadingINS_Yaw

/adma/velocity

Standard ROS topic velocity.

ROS topic fieldADMA data channel
Velocitysqrt ( INS_Vel_Hor_X_POI1 ^2 + INS_Vel_Hor_Y_POI1 ^2 )

/adma/fix

Standard ROS topic fix.

ROS topic fieldADMA data channel
StatusStatus_GNSS_Mode
AltitudeINS_Height
LatitudeINS_Lat_Abs
LongitudeINS_Long_Abs
Position_covariance[0]INS_Stddev_Lat^2
Position_covariance[4]INS_Stddev_Long^2
Position_covariance[8]INS_Stddev_Height^2
Covariance_TypeCOVARIANCE_TYPE_DIAGONAL_KNOWN

/adma/imu

Standard ROS topic imu.

ROS topic fieldADMA data channel
Linear_acceleration.xAcc_Body_HR_X * 9.81 m/s^2
Linear_acceleration.yAcc_Body_HR_Y * 9.81 m/s^2
Linear_acceleration.zAcc_Body_HR_Z * 9.81 m/s^2
Angular_velocity.xRate_Body_HR_X * π / 180
Angular_velocity.yRate_Body_HR_Y * π / 180
Angular_velocity.zRate_Body_HR_Z * π / 180
Roll_radINS_Roll * π / 180
Pitch_radINS_Pitch * π / 180
Yaw_radINS_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 fieldADMA data channel
Pose position xINS_Pos_Rel_X
Pose position yINS_Pos_Rel_Y
Pose position zINS_Height
Pose orientation xINS_Roll
Pose orientation yINS_Pitch
Pose orientation zINS_Yaw
Position_covariance[0]INS_Stddev_Lat^2
Position_covariance[4]INS_Stddev_Long^2
Position_covariance[8]INS_Stddev_Height^2
Linear twist xINS_Vel_Hor_X
Linear twist yINS_Vel_Hor_Y
Linear twist zINS_Vel_Hor_Z
Angular twist xRate_Body_X
Angular twist yRate_Body_Y
Angular twist zRate_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

Applikationsingenieur | bei GeneSys seit 2014

Notify me about Updates