This post provides an overview of the messages used by Apollo, as captured from the demo rosbag for testing the perception module.
To do:
- Investigate protobuf message definitions for variable types
- Investiage contents of standard ROS type messages
Standard message types
sensor_msgs/Image
sensor_msgs/PointCloud2
tf2_msgs/TFMessage
These messages use the standard ROS message format for their respective types.
Custom message types
Apollo uses a custom version of ROS which replaces the msg
message description language with a Real Time Publish Subscribe and Google protobuf messaging protocol for publishing and receiving the following messages.
pb_msgs/Chassis
pb_msgs/ContiRadar
pb_msgs/EpochObservation
pb_msgs/GnssBestPose
pb_msgs/GnssEphemeris
pb_msgs/GnssStatus
pb_msgs/Gps
pb_msgs/Imu
pb_msgs/InsStat
pb_msgs/LocalizationEstimate
Messages using these types cannot be interpreted using rosbag tools as only the header is compatible. However, their content can be dumped as text using read_messages()
.
Message topics
The demo rosbag contains the following topics:
topics: /apollo/canbus/chassis 5851 msgs : pb_msgs/Chassis
/apollo/localization/pose 5856 msgs : pb_msgs/LocalizationEstimate
/apollo/sensor/camera/traffic/image_long 471 msgs : sensor_msgs/Image
/apollo/sensor/camera/traffic/image_short 469 msgs : sensor_msgs/Image
/apollo/sensor/conti_radar 789 msgs : pb_msgs/ContiRadar
/apollo/sensor/gnss/best_pose 59 msgs : pb_msgs/GnssBestPose
/apollo/sensor/gnss/corrected_imu 5838 msgs : pb_msgs/Imu
/apollo/sensor/gnss/gnss_status 59 msgs : pb_msgs/GnssStatus
/apollo/sensor/gnss/imu 11630 msgs : pb_msgs/Imu
/apollo/sensor/gnss/ins_stat 118 msgs : pb_msgs/InsStat
/apollo/sensor/gnss/odometry 5848 msgs : pb_msgs/Gps
/apollo/sensor/gnss/rtk_eph 49 msgs : pb_msgs/GnssEphemeris
/apollo/sensor/gnss/rtk_obs 352 msgs : pb_msgs/EpochObservation
/apollo/sensor/velodyne64/compensator/PointCloud2 587 msgs : sensor_msgs/PointCloud2
/tf 11740 msgs : tf2_msgs/TFMessage
/tf_static 1 msg : tf2_msgs/TFMessage
Example messages
All custom messages were read using the following script, within the Apollo docker:
import rosbag
import std_msgs
from std_msgs.msg import String
bag = rosbag.Bag('../apollo_data/2018-01-03-19-37-16.bag', 'r')
read_topic = '/apollo/canbus/chassis'
counter = 0
for topic, msg, t in bag.read_messages():
if topic == read_topic:
out_file = 'messages/' + str(counter) + '.txt'
f = file(out_file, 'w')
f.write(str(msg))
f.close()
counter = counter + 1
Note that this will not work outside of the Apollo docker – the files will be empty.
pb_msgs/Chassis
Of custom protobuf type pb_msgs/Chassis
.
engine_started: true
engine_rpm: 0.0
speed_mps: 0.261111110449
odometer_m: 0.0
fuel_range_m: 0
throttle_percentage: 14.9950408936
brake_percentage: 20.5966281891
steering_percentage: 4.36170196533
steering_torque_nm: -0.75
parking_brake: false
driving_mode: COMPLETE_AUTO_DRIVE
error_code: NO_ERROR
gear_location: GEAR_DRIVE
header {
timestamp_sec: 1513807824.58
module_name: "chassis"
sequence_num: 96620
}
signal {
turn_signal: TURN_NONE
horn: false
}
chassis_gps {
latitude: 37.416912
longitude: -122.016053333
gps_valid: true
year: 17
month: 12
day: 20
hours: 22
minutes: 10
seconds: 23
compass_direction: 270.0
pdop: 0.8
is_gps_fault: false
is_inferred: false
altitude: -42.5
heading: 285.75
hdop: 0.4
vdop: 0.6
quality: FIX_3D
num_satellites: 20
gps_speed: 0.89408
}
/apollo/localization/pose
Of custom protobuf type pb_msgs/LocalizationEstimate
.
header {
timestamp_sec: 1513807826.05
module_name: "localization"
sequence_num: 96460
}
pose {
position {
x: 587068.814494
y: 4141577.34872
z: -31.0619329279
}
orientation {
qx: 0.0354450020653
qy: 0.0137914670665
qz: -0.608585615062
qw: -0.792576177036
}
linear_velocity {
x: -1.08479686092
y: 0.30964034124
z: -0.00187507107555
}
linear_acceleration {
x: -2.10530393576
y: 0.553837321635
z: 0.170289232445
}
angular_velocity {
x: 0.00630864843147
y: 0.0111583669994
z: 0.0146261464379
}
heading: 2.88124066533
linear_acceleration_vrf {
x: -0.0137881469155
y: 2.15869303259
z: 0.328470914294
}
angular_velocity_vrf {
x: 0.0120972352232
y: -0.00428235807315
z: 0.0146133729179
}
euler_angles {
x: 0.0213395674976
y: 0.0730372234802
z: -3.40194464185
}
}
measurement_time: 1513807826.04
/sensor/camera/traffic/image_long
This is a standard sensor_msgs/Image
message.
/apollo/sensor/camera/traffic/image_short
This is a standard sensor_msgs/Image
message.
/apollo/sensor/conti_radar
Of custom protobuf type pb_msgs/ContiRadar
.
header {
timestamp_sec: 1513807824.52
module_name: "conti_radar"
sequence_num: 12971
}
contiobs {
header {
timestamp_sec: 1513807824.52
module_name: "conti_radar"
sequence_num: 12971
}
clusterortrack: false
obstacle_id: 0
longitude_dist: 107.6
lateral_dist: -17.2
longitude_vel: -0.25
lateral_vel: -0.75
rcs: 7.5
dynprop: 1
longitude_dist_rms: 0.371
lateral_dist_rms: 0.616
longitude_vel_rms: 0.371
lateral_vel_rms: 0.616
probexist: 1.0
meas_state: 2
longitude_accel: 0.23
lateral_accel: 0.0
oritation_angle: 0.0
longitude_accel_rms: 0.794
lateral_accel_rms: 0.005
oritation_angle_rms: 1.909
length: 2.8
width: 2.4
obstacle_class: 1
}`
...[99 more `contiobs`]...
`object_list_status {
nof_objects: 100
meas_counter: 8464
interface_version: 0
}`
<h3>/apollo/sensor/gnss/best_pose</h3>
Of custom protobuf type `pb_msgs/GnssBestPose`.
`header {
timestamp_sec: 1513807825.02
}
measurement_time: 1197843043.0
sol_status: SOL_COMPUTED
sol_type: NARROW_INT
latitude: 37.4169108497
longitude: -122.016059063
height_msl: 2.09512365051
undulation: -32.0999984741
datum_id: WGS84
latitude_std_dev: 0.0114300707355
longitude_std_dev: 0.00970683153719
height_std_dev: 0.0248824004084
base_station_id: "0"
differential_age: 2.0
solution_age: 0.0
num_sats_tracked: 13
num_sats_in_solution: 13
num_sats_l1: 13
num_sats_multi: 11
extended_solution_status: 33
galileo_beidou_used_mask: 0
gps_glonass_used_mask: 51
/apollo/sensor/gnss/corrected_imu
Of custom protobuf type pb_msgs/Imu
.
This appears to be empty, with just a timestamp header.
/apollo/sensor/gnss/gnss_status
Of custom protobuf type pb_msgs/GnssStatus
.
header {
timestamp_sec: 1513807826.02
}
solution_completed: true
solution_status: 0
position_type: 50
num_sats: 14
/apollo/sensor/gnss/imu
Of custom protobuf type pb_msgs/Imu
.
header {
timestamp_sec: 1513807824.58
}
measurement_time: 1197843042.56
measurement_span: 0.00499999988824
linear_acceleration {
x: -0.172816216946
y: -0.864528119564
z: 9.75685194135
}
angular_velocity {
x: -0.000550057197804
y: 0.00203638196634
z: 0.00155888550527
}
/apollo/sensor/gnss/ins_stat
Of custom protobuf type pb_msgs/InsStat
.
header {
timestamp_sec: 1513807826.0
}
ins_status: 3
pos_type: 56
/apollo/sensor/gnss/odometry
Of custom protobuf type pb_msgs/Gps
.
header {
timestamp_sec: 1513807824.58
}
localization {
position {
x: 587069.287353
y: 4141577.22403
z: -31.0546750054
}
orientation {
qx: 0.0399296504032
qy: 0.0164343412444
qz: -0.606054063971
qw: -0.79425059458
}
linear_velocity {
x: -0.231635539107
y: 0.0795322332148
z: 0.00147877897123
}
}
/apollo/sensor/gnss/rtk_eph
Of custom protobuf type pb_msgs/GnssEphemeris
.
gnss_type: GPS_SYS
keppler_orbit {
gnss_type: GPS_SYS
sat_prn: 23
gnss_time_type: GPS_TIME
week_num: 1980
af0: -0.000219020526856
af1: 0.0
af2: 0.0
iode: 43.0
deltan: 5.23450375238e-09
m0: -1.97123659751
e: 0.0118623136077
roota: 5153.61836624
toe: 345600.0
toc: 345600.0
cic: 1.30385160446e-07
crc: 266.5
cis: -8.56816768646e-08
crs: -9.28125
cuc: -7.13393092155e-07
cus: 5.16884028912e-06
omega0: 2.20992318653
omega: -2.40973031377
i0: 0.943533454733
omegadot: -8.16355433052e-09
idot: -2.10723063176e-11
accuracy: 2
health: 0
tgd: -2.04890966415e-08
iodc: 43.0
}
glonass_orbit {
gnss_type: GLO_SYS
slot_prn: 10
gnss_time_type: GLO_TIME
toe: 339318.0
frequency_no: -7
week_num: 1980
week_second_s: 339318.0
tk: 3990.0
clock_offset: 1.41123309731e-05
clock_drift: 9.09494701773e-13
health: 0
position_x: -16965363.2812
position_y: -15829665.5273
position_z: -10698784.1797
velocity_x: -994.89402771
velocity_y: -1087.91637421
velocity_z: 3184.79061127
accelerate_x: -2.79396772385e-06
accelerate_y: -3.72529029846e-06
accelerate_z: -1.86264514923e-06
infor_age: 0.0
}
/apollo/sensor/gnss/rtk_obs
Of custom protobuf type pb_msgs/EpochObservation
.
receiver_id: 0
gnss_time_type: GPS_TIME
gnss_week: 1980
gnss_second_s: 339042.6
sat_obs_num: 13
sat_obs {
sat_prn: 31
sat_sys: GPS_SYS
band_obs_num: 2
band_obs {
band_id: GPS_L1
frequency_value: 0.0
pseudo_type: CORSE_CODE
pseudo_range: 22104170.8773
carrier_phase: 116158209.251
loss_lock_index: 173
doppler: -2880.74853516
snr: 173.0
}
band_obs {
band_id: GPS_L2
frequency_value: 0.0
pseudo_type: CORSE_CODE
pseudo_range: 22104174.5591
carrier_phase: 90512897.445
loss_lock_index: 140
doppler: -2244.73510742
snr: 140.0
}
}
…[13 more sat_obs
]…
/apollo/sensor/velodyne64/compensator/PointCloud2
This is a standard sensor_msgs/PointCloud2
message.
/tf
This is a standard tf2_msgs/TFMessage
message. The messages alternate between frame_id: world
to child_frame_id: localization
transform messages and frame_id: world
to child_frame_id: novatel
transform messages.
/tf_static
This is a standard tf2_msgs/TFMessage
message, for the frame_id: novatel
to velodyne64
transform.