From f17ffb1e04710ac6e24ad1c94ea5cb78b4dc9054 Mon Sep 17 00:00:00 2001 From: Tobias Neumann Date: Wed, 16 Aug 2023 14:28:21 +0200 Subject: [PATCH] RadarReturn: add duration as offset from stamp in RadarScan RadarScan: clearify that the stamp in the header should be the first measurement of this scan. --- msg/RadarReturn.msg | 2 ++ msg/RadarScan.msg | 3 ++- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/msg/RadarReturn.msg b/msg/RadarReturn.msg index f353801..264b0c7 100644 --- a/msg/RadarReturn.msg +++ b/msg/RadarReturn.msg @@ -1,6 +1,8 @@ # 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. +builtin_interfaces/Duration stamp_offset # Offset to the stamp in the RadarScan message. + # If the offset is unknown it should be set to 0. 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. diff --git a/msg/RadarScan.msg b/msg/RadarScan.msg index 7735da4..4ac9ed9 100644 --- a/msg/RadarScan.msg +++ b/msg/RadarScan.msg @@ -1,3 +1,4 @@ -std_msgs/Header header +std_msgs/Header header # timestamp in the header is the acquisition time of + # the first beam in the scan. radar_msgs/RadarReturn[] returns