diff --git a/msg/RadarReturn.msg b/msg/RadarReturn.msg new file mode 100644 index 0000000..9026697 --- /dev/null +++ b/msg/RadarReturn.msg @@ -0,0 +1,10 @@ +# All variables below are relative to the radar's frame of reference. +# This message is not meant to be used alone but as part of a stamped or array message. + +float32 range # Distance (m) from the sensor to the detected return. +float32 azimuth # Angle (in radians) in the azimuth plane between the sensor and the detected return. + # Positive angles are anticlockwise from the sensor and negative angles clockwise from the sensor as per REP-0103. +float32 elevation # Angle (in radians) in the elevation plane between the sensor and the detected return. + # Negative angles are below the sensor. For 2D radar, this will be 0. +float32 doppler_velocity # The doppler speeds (m/s) of the return. +float32 amplitude # The amplitude of the of the return (dB) diff --git a/msg/RadarScan.msg b/msg/RadarScan.msg new file mode 100644 index 0000000..7735da4 --- /dev/null +++ b/msg/RadarScan.msg @@ -0,0 +1,3 @@ +std_msgs/Header header + +radar_msgs/RadarReturn[] returns