Skip to content

Commit

Permalink
Added new proximity sensor message.
Browse files Browse the repository at this point in the history
  • Loading branch information
pcdangio committed May 30, 2019
1 parent 77be78b commit a4135bb
Show file tree
Hide file tree
Showing 3 changed files with 19 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,7 @@ add_message_files(
FILES
AxisState.msg
AxisDelta.msg
Proximity.msg
)

## Generate services in the 'srv' folder
Expand Down
17 changes: 17 additions & 0 deletions msg/Proximity.msg
Original file line number Diff line number Diff line change
@@ -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.
1 change: 1 addition & 0 deletions sensor_msgs_ext.pro
Original file line number Diff line number Diff line change
Expand Up @@ -7,5 +7,6 @@ DISTFILES += \
CMakeLists.txt \
msg/AxisDelta.msg \
msg/AxisState.msg \
msg/Proximity.msg \
package.xml \
srv/SetAxisHome.srv

0 comments on commit a4135bb

Please sign in to comment.