From a4135bb44052f3b023e850186a529fd603528012 Mon Sep 17 00:00:00 2001 From: Paul D'Angio Date: Wed, 29 May 2019 20:17:50 -0400 Subject: [PATCH] Added new proximity sensor message. --- CMakeLists.txt | 1 + msg/Proximity.msg | 17 +++++++++++++++++ sensor_msgs_ext.pro | 1 + 3 files changed, 19 insertions(+) create mode 100644 msg/Proximity.msg diff --git a/CMakeLists.txt b/CMakeLists.txt index ba5fff1..ac67380 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,6 +47,7 @@ add_message_files( FILES AxisState.msg AxisDelta.msg + Proximity.msg ) ## Generate services in the 'srv' folder diff --git a/msg/Proximity.msg b/msg/Proximity.msg new file mode 100644 index 0000000..75f9050 --- /dev/null +++ b/msg/Proximity.msg @@ -0,0 +1,17 @@ +# Reports the instantaneous measurement of a proximity sensor. + +Header header # Includes a timestamp and frame ID for the measurement. + +# Radiation enumerations. +uint8 UNSPECIFIED=255 +uint8 ULTRASOUND=0 +uint8 INFRARED=1 +uint8 RADAR=2 + +uint8 radiation_type # The type of radiation used by the sensor (e.g. ULTRASOUND, INFRARED, RADAR) + +float32 min_range # The minimum detection range of the sensor [m] +float32 max_range # The maximum detection range of the sensor [m] +float32 field_of_view # The maximum FoV of the sensor [rad] + +bool proximity # Reports TRUE if proximity is detected, otherwise FALSE. diff --git a/sensor_msgs_ext.pro b/sensor_msgs_ext.pro index 2fa9558..35398d8 100644 --- a/sensor_msgs_ext.pro +++ b/sensor_msgs_ext.pro @@ -7,5 +7,6 @@ DISTFILES += \ CMakeLists.txt \ msg/AxisDelta.msg \ msg/AxisState.msg \ + msg/Proximity.msg \ package.xml \ srv/SetAxisHome.srv