mirror of https://github.com/ArduPilot/ardupilot
AP_UAVCAN: added safety LED and button messages
This commit is contained in:
parent
0ea67943b9
commit
39f4f7c208
|
@ -0,0 +1,8 @@
|
||||||
|
This directory contains the DSDL for the ArduPilot vendor specific
|
||||||
|
UAVCAN messages.
|
||||||
|
|
||||||
|
For service messages we use IDs starting at 200
|
||||||
|
|
||||||
|
For non-service messages we use IDs starting at 20000
|
||||||
|
|
||||||
|
https://uavcan.org/Specification/5._Application_level_conventions/#id-distribution
|
|
@ -0,0 +1,7 @@
|
||||||
|
#
|
||||||
|
# support for Safety LED on UAVCAN
|
||||||
|
|
||||||
|
uint8 STATUS_SAFETY_ON = 0
|
||||||
|
uint8 STATUS_SAFETY_OFF = 255
|
||||||
|
|
||||||
|
uint8 status
|
|
@ -0,0 +1,11 @@
|
||||||
|
#
|
||||||
|
# support for buttons on UAVCAN
|
||||||
|
# while a button is being pressed this message should be sent at 10Hz
|
||||||
|
|
||||||
|
uint8 BUTTON_SAFETY = 1
|
||||||
|
|
||||||
|
uint8 button
|
||||||
|
|
||||||
|
# number of 0.1s units the button has been pressed for. If over 255
|
||||||
|
# then send 255
|
||||||
|
uint8 press_time
|
Loading…
Reference in New Issue