aboutsummaryrefslogtreecommitdiff
path: root/msg
diff options
context:
space:
mode:
Diffstat (limited to 'msg')
-rw-r--r--msg/actuator_armed.msg6
-rw-r--r--msg/actuator_controls.msg4
-rw-r--r--msg/actuator_controls_0.msg4
-rw-r--r--msg/manual_control_setpoint.msg44
-rw-r--r--msg/parameter_update.msg1
-rw-r--r--msg/rc_channels.msg24
-rw-r--r--msg/std_msgs/Bool.msg1
-rw-r--r--msg/std_msgs/Byte.msg1
-rw-r--r--msg/std_msgs/ByteMultiArray.msg6
-rw-r--r--msg/std_msgs/Char.msg1
-rw-r--r--msg/std_msgs/ColorRGBA.msg4
-rw-r--r--msg/std_msgs/Duration.msg1
-rw-r--r--msg/std_msgs/Empty.msg0
-rw-r--r--msg/std_msgs/Float32.msg1
-rw-r--r--msg/std_msgs/Float32MultiArray.msg6
-rw-r--r--msg/std_msgs/Float64.msg1
-rw-r--r--msg/std_msgs/Float64MultiArray.msg6
-rw-r--r--msg/std_msgs/Header.msg15
-rw-r--r--msg/std_msgs/Int16.msg1
-rw-r--r--msg/std_msgs/Int16MultiArray.msg6
-rw-r--r--msg/std_msgs/Int32.msg1
-rw-r--r--msg/std_msgs/Int32MultiArray.msg6
-rw-r--r--msg/std_msgs/Int64.msg1
-rw-r--r--msg/std_msgs/Int64MultiArray.msg6
-rw-r--r--msg/std_msgs/Int8.msg1
-rw-r--r--msg/std_msgs/Int8MultiArray.msg6
-rw-r--r--msg/std_msgs/MultiArrayDimension.msg3
-rw-r--r--msg/std_msgs/MultiArrayLayout.msg26
-rw-r--r--msg/std_msgs/String.msg1
-rw-r--r--msg/std_msgs/Time.msg1
-rw-r--r--msg/std_msgs/UInt16.msg1
-rw-r--r--msg/std_msgs/UInt16MultiArray.msg6
-rw-r--r--msg/std_msgs/UInt32.msg1
-rw-r--r--msg/std_msgs/UInt32MultiArray.msg6
-rw-r--r--msg/std_msgs/UInt64.msg1
-rw-r--r--msg/std_msgs/UInt64MultiArray.msg6
-rw-r--r--msg/std_msgs/UInt8.msg1
-rw-r--r--msg/std_msgs/UInt8MultiArray.msg6
-rw-r--r--msg/templates/msg.h.template153
-rw-r--r--msg/vehicle_attitude.msg35
-rw-r--r--msg/vehicle_attitude_setpoint.msg21
-rw-r--r--msg/vehicle_control_mode.msg22
-rw-r--r--msg/vehicle_rates_setpoint.msg6
-rw-r--r--msg/vehicle_status.msg158
44 files changed, 608 insertions, 0 deletions
diff --git a/msg/actuator_armed.msg b/msg/actuator_armed.msg
new file mode 100644
index 000000000..b83adb8f2
--- /dev/null
+++ b/msg/actuator_armed.msg
@@ -0,0 +1,6 @@
+
+uint64 timestamp # Microseconds since system boot
+bool armed # Set to true if system is armed
+bool ready_to_arm # Set to true if system is ready to be armed
+bool lockdown # Set to true if actuators are forced to being disabled (due to emergency or HIL)
+bool force_failsafe # Set to true if the actuators are forced to the failsafe position
diff --git a/msg/actuator_controls.msg b/msg/actuator_controls.msg
new file mode 100644
index 000000000..743f20cdf
--- /dev/null
+++ b/msg/actuator_controls.msg
@@ -0,0 +1,4 @@
+uint8 NUM_ACTUATOR_CONTROLS = 8
+uint8 NUM_ACTUATOR_CONTROL_GROUPS = 4
+uint64 timestamp
+float32[8] control
diff --git a/msg/actuator_controls_0.msg b/msg/actuator_controls_0.msg
new file mode 100644
index 000000000..743f20cdf
--- /dev/null
+++ b/msg/actuator_controls_0.msg
@@ -0,0 +1,4 @@
+uint8 NUM_ACTUATOR_CONTROLS = 8
+uint8 NUM_ACTUATOR_CONTROL_GROUPS = 4
+uint64 timestamp
+float32[8] control
diff --git a/msg/manual_control_setpoint.msg b/msg/manual_control_setpoint.msg
new file mode 100644
index 000000000..d3cfb078b
--- /dev/null
+++ b/msg/manual_control_setpoint.msg
@@ -0,0 +1,44 @@
+
+uint8 SWITCH_POS_NONE = 0 # switch is not mapped
+uint8 SWITCH_POS_ON = 1 # switch activated (value = 1)
+uint8 SWITCH_POS_MIDDLE = 2 # middle position (value = 0)
+uint8 SWITCH_POS_OFF = 3 # switch not activated (value = -1)
+uint64 timestamp
+
+# Any of the channels may not be available and be set to NaN
+# to indicate that it does not contain valid data.
+# The variable names follow the definition of the
+# MANUAL_CONTROL mavlink message.
+# The default range is from -1 to 1 (mavlink message -1000 to 1000)
+# The range for the z variable is defined from 0 to 1. (The z field of
+# the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
+
+float32 x # stick position in x direction -1..1
+ # in general corresponds to forward/back motion or pitch of vehicle,
+ # in general a positive value means forward or negative pitch and
+ # a negative value means backward or positive pitch
+float32 y # stick position in y direction -1..1
+ # in general corresponds to right/left motion or roll of vehicle,
+ # in general a positive value means right or positive roll and
+ # a negative value means left or negative roll
+float32 z # throttle stick position 0..1
+ # in general corresponds to up/down motion or thrust of vehicle,
+ # in general the value corresponds to the demanded throttle by the user,
+ # if the input is used for setting the setpoint of a vertical position
+ # controller any value > 0.5 means up and any value < 0.5 means down
+float32 r # yaw stick/twist positon, -1..1
+ # in general corresponds to the righthand rotation around the vertical
+ # (downwards) axis of the vehicle
+float32 flaps # flap position
+float32 aux1 # default function: camera yaw / azimuth
+float32 aux2 # default function: camera pitch / tilt
+float32 aux3 # default function: camera trigger
+float32 aux4 # default function: camera roll
+float32 aux5 # default function: payload drop
+
+uint8 mode_switch # main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO
+uint8 return_switch # return to launch 2 position switch (mandatory): _NORMAL_, RTL
+uint8 posctl_switch # position control 2 position switch (optional): _ALTCTL_, POSCTL
+uint8 loiter_switch # loiter 2 position switch (optional): _MISSION_, LOITER
+uint8 acro_switch # acro 2 position switch (optional): _MANUAL_, ACRO
+uint8 offboard_switch # offboard 2 position switch (optional): _NORMAL_, OFFBOARD
diff --git a/msg/parameter_update.msg b/msg/parameter_update.msg
new file mode 100644
index 000000000..39dc336e0
--- /dev/null
+++ b/msg/parameter_update.msg
@@ -0,0 +1 @@
+uint64 timestamp # time at which the latest parameter was updated
diff --git a/msg/rc_channels.msg b/msg/rc_channels.msg
new file mode 100644
index 000000000..4e0e5b494
--- /dev/null
+++ b/msg/rc_channels.msg
@@ -0,0 +1,24 @@
+int32 RC_CHANNELS_FUNCTION_MAX=18
+uint8 RC_CHANNELS_FUNCTION_THROTTLE=0
+uint8 RC_CHANNELS_FUNCTION_ROLL=1
+uint8 RC_CHANNELS_FUNCTION_PITCH=2
+uint8 RC_CHANNELS_FUNCTION_YAW=3
+uint8 RC_CHANNELS_FUNCTION_MODE=4
+uint8 RC_CHANNELS_FUNCTION_RETURN=5
+uint8 RC_CHANNELS_FUNCTION_POSCTL=6
+uint8 RC_CHANNELS_FUNCTION_LOITER=7
+uint8 RC_CHANNELS_FUNCTION_OFFBOARD=8
+uint8 RC_CHANNELS_FUNCTION_ACRO=9
+uint8 RC_CHANNELS_FUNCTION_FLAPS=10
+uint8 RC_CHANNELS_FUNCTION_AUX_1=11
+uint8 RC_CHANNELS_FUNCTION_AUX_2=12
+uint8 RC_CHANNELS_FUNCTION_AUX_3=13
+uint8 RC_CHANNELS_FUNCTION_AUX_4=14
+uint8 RC_CHANNELS_FUNCTION_AUX_5=15
+uint64 timestamp # Timestamp in microseconds since boot time
+uint64 timestamp_last_valid # Timestamp of last valid RC signal
+float32[18] channels # Scaled to -1..1 (throttle: 0..1)
+uint8 channel_count # Number of valid channels
+int8[18] function # Functions mapping
+uint8 rssi # Receive signal strength index
+bool signal_lost # Control signal lost, should be checked together with topic timeout
diff --git a/msg/std_msgs/Bool.msg b/msg/std_msgs/Bool.msg
new file mode 100644
index 000000000..f7cabb94f
--- /dev/null
+++ b/msg/std_msgs/Bool.msg
@@ -0,0 +1 @@
+bool data \ No newline at end of file
diff --git a/msg/std_msgs/Byte.msg b/msg/std_msgs/Byte.msg
new file mode 100644
index 000000000..d993b3455
--- /dev/null
+++ b/msg/std_msgs/Byte.msg
@@ -0,0 +1 @@
+byte data
diff --git a/msg/std_msgs/ByteMultiArray.msg b/msg/std_msgs/ByteMultiArray.msg
new file mode 100644
index 000000000..bb00bd348
--- /dev/null
+++ b/msg/std_msgs/ByteMultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+byte[] data # array of data
+
diff --git a/msg/std_msgs/Char.msg b/msg/std_msgs/Char.msg
new file mode 100644
index 000000000..39a1d46a9
--- /dev/null
+++ b/msg/std_msgs/Char.msg
@@ -0,0 +1 @@
+char data \ No newline at end of file
diff --git a/msg/std_msgs/ColorRGBA.msg b/msg/std_msgs/ColorRGBA.msg
new file mode 100644
index 000000000..182dbc834
--- /dev/null
+++ b/msg/std_msgs/ColorRGBA.msg
@@ -0,0 +1,4 @@
+float32 r
+float32 g
+float32 b
+float32 a
diff --git a/msg/std_msgs/Duration.msg b/msg/std_msgs/Duration.msg
new file mode 100644
index 000000000..f13931ec8
--- /dev/null
+++ b/msg/std_msgs/Duration.msg
@@ -0,0 +1 @@
+duration data
diff --git a/msg/std_msgs/Empty.msg b/msg/std_msgs/Empty.msg
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/msg/std_msgs/Empty.msg
diff --git a/msg/std_msgs/Float32.msg b/msg/std_msgs/Float32.msg
new file mode 100644
index 000000000..e89740534
--- /dev/null
+++ b/msg/std_msgs/Float32.msg
@@ -0,0 +1 @@
+float32 data \ No newline at end of file
diff --git a/msg/std_msgs/Float32MultiArray.msg b/msg/std_msgs/Float32MultiArray.msg
new file mode 100644
index 000000000..915830846
--- /dev/null
+++ b/msg/std_msgs/Float32MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+float32[] data # array of data
+
diff --git a/msg/std_msgs/Float64.msg b/msg/std_msgs/Float64.msg
new file mode 100644
index 000000000..cd09d39b8
--- /dev/null
+++ b/msg/std_msgs/Float64.msg
@@ -0,0 +1 @@
+float64 data \ No newline at end of file
diff --git a/msg/std_msgs/Float64MultiArray.msg b/msg/std_msgs/Float64MultiArray.msg
new file mode 100644
index 000000000..0a13b928f
--- /dev/null
+++ b/msg/std_msgs/Float64MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+float64[] data # array of data
+
diff --git a/msg/std_msgs/Header.msg b/msg/std_msgs/Header.msg
new file mode 100644
index 000000000..f90d622ea
--- /dev/null
+++ b/msg/std_msgs/Header.msg
@@ -0,0 +1,15 @@
+# Standard metadata for higher-level stamped data types.
+# This is generally used to communicate timestamped data
+# in a particular coordinate frame.
+#
+# sequence ID: consecutively increasing ID
+uint32 seq
+#Two-integer timestamp that is expressed as:
+# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')
+# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')
+# time-handling sugar is provided by the client library
+time stamp
+#Frame this data is associated with
+# 0: no frame
+# 1: global frame
+string frame_id
diff --git a/msg/std_msgs/Int16.msg b/msg/std_msgs/Int16.msg
new file mode 100644
index 000000000..c4389faf7
--- /dev/null
+++ b/msg/std_msgs/Int16.msg
@@ -0,0 +1 @@
+int16 data
diff --git a/msg/std_msgs/Int16MultiArray.msg b/msg/std_msgs/Int16MultiArray.msg
new file mode 100644
index 000000000..d2ddea1d1
--- /dev/null
+++ b/msg/std_msgs/Int16MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int16[] data # array of data
+
diff --git a/msg/std_msgs/Int32.msg b/msg/std_msgs/Int32.msg
new file mode 100644
index 000000000..0ecfe35f5
--- /dev/null
+++ b/msg/std_msgs/Int32.msg
@@ -0,0 +1 @@
+int32 data \ No newline at end of file
diff --git a/msg/std_msgs/Int32MultiArray.msg b/msg/std_msgs/Int32MultiArray.msg
new file mode 100644
index 000000000..af60abda3
--- /dev/null
+++ b/msg/std_msgs/Int32MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int32[] data # array of data
+
diff --git a/msg/std_msgs/Int64.msg b/msg/std_msgs/Int64.msg
new file mode 100644
index 000000000..6961e00f5
--- /dev/null
+++ b/msg/std_msgs/Int64.msg
@@ -0,0 +1 @@
+int64 data \ No newline at end of file
diff --git a/msg/std_msgs/Int64MultiArray.msg b/msg/std_msgs/Int64MultiArray.msg
new file mode 100644
index 000000000..f4f35e171
--- /dev/null
+++ b/msg/std_msgs/Int64MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int64[] data # array of data
+
diff --git a/msg/std_msgs/Int8.msg b/msg/std_msgs/Int8.msg
new file mode 100644
index 000000000..1e42e554f
--- /dev/null
+++ b/msg/std_msgs/Int8.msg
@@ -0,0 +1 @@
+int8 data
diff --git a/msg/std_msgs/Int8MultiArray.msg b/msg/std_msgs/Int8MultiArray.msg
new file mode 100644
index 000000000..a59a37259
--- /dev/null
+++ b/msg/std_msgs/Int8MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+int8[] data # array of data
+
diff --git a/msg/std_msgs/MultiArrayDimension.msg b/msg/std_msgs/MultiArrayDimension.msg
new file mode 100644
index 000000000..08240462c
--- /dev/null
+++ b/msg/std_msgs/MultiArrayDimension.msg
@@ -0,0 +1,3 @@
+string label # label of given dimension
+uint32 size # size of given dimension (in type units)
+uint32 stride # stride of given dimension \ No newline at end of file
diff --git a/msg/std_msgs/MultiArrayLayout.msg b/msg/std_msgs/MultiArrayLayout.msg
new file mode 100644
index 000000000..5437f8542
--- /dev/null
+++ b/msg/std_msgs/MultiArrayLayout.msg
@@ -0,0 +1,26 @@
+# The multiarray declares a generic multi-dimensional array of a
+# particular data type. Dimensions are ordered from outer most
+# to inner most.
+
+MultiArrayDimension[] dim # Array of dimension properties
+uint32 data_offset # padding bytes at front of data
+
+# Accessors should ALWAYS be written in terms of dimension stride
+# and specified outer-most dimension first.
+#
+# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
+#
+# A standard, 3-channel 640x480 image with interleaved color channels
+# would be specified as:
+#
+# dim[0].label = "height"
+# dim[0].size = 480
+# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)
+# dim[1].label = "width"
+# dim[1].size = 640
+# dim[1].stride = 3*640 = 1920
+# dim[2].label = "channel"
+# dim[2].size = 3
+# dim[2].stride = 3
+#
+# multiarray(i,j,k) refers to the ith row, jth column, and kth channel. \ No newline at end of file
diff --git a/msg/std_msgs/String.msg b/msg/std_msgs/String.msg
new file mode 100644
index 000000000..ae721739e
--- /dev/null
+++ b/msg/std_msgs/String.msg
@@ -0,0 +1 @@
+string data
diff --git a/msg/std_msgs/Time.msg b/msg/std_msgs/Time.msg
new file mode 100644
index 000000000..7f8f72171
--- /dev/null
+++ b/msg/std_msgs/Time.msg
@@ -0,0 +1 @@
+time data
diff --git a/msg/std_msgs/UInt16.msg b/msg/std_msgs/UInt16.msg
new file mode 100644
index 000000000..87d0c44eb
--- /dev/null
+++ b/msg/std_msgs/UInt16.msg
@@ -0,0 +1 @@
+uint16 data
diff --git a/msg/std_msgs/UInt16MultiArray.msg b/msg/std_msgs/UInt16MultiArray.msg
new file mode 100644
index 000000000..f38970b65
--- /dev/null
+++ b/msg/std_msgs/UInt16MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint16[] data # array of data
+
diff --git a/msg/std_msgs/UInt32.msg b/msg/std_msgs/UInt32.msg
new file mode 100644
index 000000000..b6c696b42
--- /dev/null
+++ b/msg/std_msgs/UInt32.msg
@@ -0,0 +1 @@
+uint32 data \ No newline at end of file
diff --git a/msg/std_msgs/UInt32MultiArray.msg b/msg/std_msgs/UInt32MultiArray.msg
new file mode 100644
index 000000000..b2bb0771f
--- /dev/null
+++ b/msg/std_msgs/UInt32MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint32[] data # array of data
+
diff --git a/msg/std_msgs/UInt64.msg b/msg/std_msgs/UInt64.msg
new file mode 100644
index 000000000..2eb1afad3
--- /dev/null
+++ b/msg/std_msgs/UInt64.msg
@@ -0,0 +1 @@
+uint64 data \ No newline at end of file
diff --git a/msg/std_msgs/UInt64MultiArray.msg b/msg/std_msgs/UInt64MultiArray.msg
new file mode 100644
index 000000000..30d0cd928
--- /dev/null
+++ b/msg/std_msgs/UInt64MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint64[] data # array of data
+
diff --git a/msg/std_msgs/UInt8.msg b/msg/std_msgs/UInt8.msg
new file mode 100644
index 000000000..5eefd870d
--- /dev/null
+++ b/msg/std_msgs/UInt8.msg
@@ -0,0 +1 @@
+uint8 data
diff --git a/msg/std_msgs/UInt8MultiArray.msg b/msg/std_msgs/UInt8MultiArray.msg
new file mode 100644
index 000000000..31f7d6a21
--- /dev/null
+++ b/msg/std_msgs/UInt8MultiArray.msg
@@ -0,0 +1,6 @@
+# Please look at the MultiArrayLayout message definition for
+# documentation on all multiarrays.
+
+MultiArrayLayout layout # specification of data layout
+uint8[] data # array of data
+
diff --git a/msg/templates/msg.h.template b/msg/templates/msg.h.template
new file mode 100644
index 000000000..19068a3a1
--- /dev/null
+++ b/msg/templates/msg.h.template
@@ -0,0 +1,153 @@
+@###############################################
+@#
+@# PX4 ROS compatible message source code
+@# generation for C++
+@#
+@# EmPy template for generating <msg>.h files
+@# Based on the original template for ROS
+@#
+@###############################################
+@# Start of Template
+@#
+@# Context:
+@# - file_name_in (String) Source file
+@# - spec (msggen.MsgSpec) Parsed specification of the .msg file
+@# - md5sum (String) MD5Sum of the .msg specification
+@###############################################
+/****************************************************************************
+ *
+ * Copyright (C) 2013-2014 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+ /* Auto-generated by genmsg_cpp from file @file_name_in */
+
+@{
+import genmsg.msgs
+import gencpp
+
+cpp_namespace = '::%s::'%(spec.package) # TODO handle nested namespace
+cpp_class = '%s_'%spec.short_name
+cpp_full_name = '%s%s'%(cpp_namespace,cpp_class)
+cpp_full_name_with_alloc = '%s<ContainerAllocator>'%(cpp_full_name)
+cpp_msg_definition = gencpp.escape_message_definition(msg_definition)
+}@
+
+#pragma once
+
+@##############################
+@# Generic Includes
+@##############################
+#include <stdint.h>
+#include "../uORB.h"
+
+@##############################
+@# Includes for dependencies
+@##############################
+@{
+for field in spec.parsed_fields():
+ if (not field.is_builtin):
+ if (not field.is_header):
+ (package, name) = genmsg.names.package_resource_name(field.base_type)
+ package = package or spec.package # convert '' to package
+ print('#include <uORB/topics/%s.h>'%(name))
+
+}@
+@# Constants
+@[for constant in spec.constants]@
+#define @(constant.name) @(int(constant.val))
+@[end for]
+
+/**
+ * @@addtogroup topics
+ * @@{
+ */
+
+@##############################
+@# Main struct of message
+@##############################
+@{
+
+type_map = {'int8': 'int8_t',
+ 'int16': 'int16_t',
+ 'int32': 'int32_t',
+ 'int64': 'int64_t',
+ 'uint8': 'uint8_t',
+ 'uint16': 'uint16_t',
+ 'uint32': 'uint32_t',
+ 'uint64': 'uint64_t',
+ 'float32': 'float',
+ 'bool': 'bool',
+ 'fence_vertex': 'fence_vertex'}
+
+# Function to print a standard ros type
+def print_field_def(field):
+ type = field.type
+ # detect embedded types
+ sl_pos = type.find('/')
+ type_appendix = ''
+ type_prefix = ''
+ if (sl_pos >= 0):
+ type = type[sl_pos + 1:]
+ type_prefix = 'struct '
+ type_appendix = '_s'
+
+ # detect arrays
+ a_pos = type.find('[')
+ array_size = ''
+ if (a_pos >= 0):
+ # field is array
+ array_size = type[a_pos:]
+ type = type[:a_pos]
+
+ if type in type_map:
+ # need to add _t: int8 --> int8_t
+ type_px4 = type_map[type]
+ else:
+ raise Exception("Type {0} not supported, add to to template file!".format(type))
+
+ print('\t%s%s%s %s%s;'%(type_prefix, type_px4, type_appendix, field.name, array_size))
+
+}
+struct @(spec.short_name)_s {
+@{
+# loop over all fields and print the type and name
+for field in spec.parsed_fields():
+ if (not field.is_header):
+ print_field_def(field)
+}@
+};
+
+/**
+ * @@}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(@(spec.short_name));
diff --git a/msg/vehicle_attitude.msg b/msg/vehicle_attitude.msg
new file mode 100644
index 000000000..dbfd8b6bc
--- /dev/null
+++ b/msg/vehicle_attitude.msg
@@ -0,0 +1,35 @@
+# This is similar to the mavlink message ATTITUDE, but for onboard use */
+uint64 timestamp # in microseconds since system start
+# @warning roll, pitch and yaw have always to be valid, the rotation matrix and quaternion are optional
+float32 roll # Roll angle (rad, Tait-Bryan, NED)
+float32 pitch # Pitch angle (rad, Tait-Bryan, NED)
+float32 yaw # Yaw angle (rad, Tait-Bryan, NED)
+float32 rollspeed # Roll angular speed (rad/s, Tait-Bryan, NED)
+float32 pitchspeed # Pitch angular speed (rad/s, Tait-Bryan, NED)
+float32 yawspeed # Yaw angular speed (rad/s, Tait-Bryan, NED)
+float32 rollacc # Roll angular accelration (rad/s, Tait-Bryan, NED)
+float32 pitchacc # Pitch angular acceleration (rad/s, Tait-Bryan, NED)
+float32 yawacc # Yaw angular acceleration (rad/s, Tait-Bryan, NED)
+float32[3] rate_offsets # Offsets of the body angular rates from zero
+float32[9] R # Rotation matrix, body to world, (Tait-Bryan, NED)
+float32[4] q # Quaternion (NED)
+float32[3] g_comp # Compensated gravity vector
+bool R_valid # Rotation matrix valid
+bool q_valid # Quaternion valid
+
+# secondary attitude for VTOL
+float32 roll_sec # Roll angle (rad, Tait-Bryan, NED)
+float32 pitch_sec # Pitch angle (rad, Tait-Bryan, NED)
+float32 yaw_sec # Yaw angle (rad, Tait-Bryan, NED)
+float32 rollspeed_sec # Roll angular speed (rad/s, Tait-Bryan, NED)
+float32 pitchspeed_sec # Pitch angular speed (rad/s, Tait-Bryan, NED)
+float32 yawspeed_sec # Yaw angular speed (rad/s, Tait-Bryan, NED)
+float32 rollacc_sec # Roll angular accelration (rad/s, Tait-Bryan, NED)
+float32 pitchacc_sec # Pitch angular acceleration (rad/s, Tait-Bryan, NED)
+float32 yawacc_sec # Yaw angular acceleration (rad/s, Tait-Bryan, NED)
+float32[3] rate_offsets_sec # Offsets of the body angular rates from zero
+float32[9] R_sec # Rotation matrix, body to world, (Tait-Bryan, NED)
+float32[4] q_sec # Quaternion (NED)
+float32[3] g_comp_sec # Compensated gravity vector
+bool R_valid_sec # Rotation matrix valid
+bool q_valid_sec # Quaternion valid
diff --git a/msg/vehicle_attitude_setpoint.msg b/msg/vehicle_attitude_setpoint.msg
new file mode 100644
index 000000000..1a8e6e3d5
--- /dev/null
+++ b/msg/vehicle_attitude_setpoint.msg
@@ -0,0 +1,21 @@
+
+uint64 timestamp # in microseconds since system start, is set whenever the writing thread stores new data
+
+float32 roll_body # body angle in NED frame
+float32 pitch_body # body angle in NED frame
+float32 yaw_body # body angle in NED frame
+
+float32[9] R_body # Rotation matrix describing the setpoint as rotation from the current body frame
+bool R_valid # Set to true if rotation matrix is valid
+
+# For quaternion-based attitude control
+float32[4] q_d # Desired quaternion for quaternion control
+bool q_d_valid # Set to true if quaternion vector is valid
+float32[4] q_e # Attitude error in quaternion
+bool q_e_valid # Set to true if quaternion error vector is valid
+
+float32 thrust # Thrust in Newton the power system should generate
+
+bool roll_reset_integral # Reset roll integral part (navigation logic change)
+bool pitch_reset_integral # Reset pitch integral part (navigation logic change)
+bool yaw_reset_integral # Reset yaw integral part (navigation logic change)
diff --git a/msg/vehicle_control_mode.msg b/msg/vehicle_control_mode.msg
new file mode 100644
index 000000000..153a642bb
--- /dev/null
+++ b/msg/vehicle_control_mode.msg
@@ -0,0 +1,22 @@
+
+uint64 timestamp # in microseconds since system start
+ # is set whenever the writing thread stores new data
+
+bool flag_armed
+
+bool flag_external_manual_override_ok # external override non-fatal for system. Only true for fixed wing
+
+# XXX needs yet to be set by state machine helper
+bool flag_system_hil_enabled
+
+bool flag_control_manual_enabled # true if manual input is mixed in
+bool flag_control_auto_enabled # true if onboard autopilot should act
+bool flag_control_offboard_enabled # true if offboard control should be used
+bool flag_control_rates_enabled # true if rates are stabilized
+bool flag_control_attitude_enabled # true if attitude stabilization is mixed in
+bool flag_control_force_enabled # true if force control is mixed in
+bool flag_control_velocity_enabled # true if horizontal velocity (implies direction) is controlled
+bool flag_control_position_enabled # true if position is controlled
+bool flag_control_altitude_enabled # true if altitude is controlled
+bool flag_control_climb_rate_enabled # true if climb rate is controlled
+bool flag_control_termination_enabled # true if flighttermination is enabled
diff --git a/msg/vehicle_rates_setpoint.msg b/msg/vehicle_rates_setpoint.msg
new file mode 100644
index 000000000..834113c79
--- /dev/null
+++ b/msg/vehicle_rates_setpoint.msg
@@ -0,0 +1,6 @@
+uint64 timestamp # in microseconds since system start
+
+float32 roll # body angular rates in NED frame
+float32 pitch # body angular rates in NED frame
+float32 yaw # body angular rates in NED frame
+float32 thrust # thrust normalized to 0..1
diff --git a/msg/vehicle_status.msg b/msg/vehicle_status.msg
new file mode 100644
index 000000000..21a088f12
--- /dev/null
+++ b/msg/vehicle_status.msg
@@ -0,0 +1,158 @@
+# Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link.
+uint8 MAIN_STATE_MANUAL = 0
+uint8 MAIN_STATE_ALTCTL = 1
+uint8 MAIN_STATE_POSCTL = 2
+uint8 MAIN_STATE_AUTO_MISSION = 3
+uint8 MAIN_STATE_AUTO_LOITER = 4
+uint8 MAIN_STATE_AUTO_RTL = 5
+uint8 MAIN_STATE_ACRO = 6
+uint8 MAIN_STATE_OFFBOARD = 7
+uint8 MAIN_STATE_MAX = 8
+
+# If you change the order, add or remove arming_state_t states make sure to update the arrays
+# in state_machine_helper.cpp as well.
+uint8 ARMING_STATE_INIT = 0
+uint8 ARMING_STATE_STANDBY = 1
+uint8 ARMING_STATE_ARMED = 2
+uint8 ARMING_STATE_ARMED_ERROR = 3
+uint8 ARMING_STATE_STANDBY_ERROR = 4
+uint8 ARMING_STATE_REBOOT = 5
+uint8 ARMING_STATE_IN_AIR_RESTORE = 6
+uint8 ARMING_STATE_MAX = 7
+
+uint8 HIL_STATE_OFF = 0
+uint8 HIL_STATE_ON = 1
+
+# Navigation state, i.e. "what should vehicle do".
+uint8 NAVIGATION_STATE_MANUAL = 0 # Manual mode
+uint8 NAVIGATION_STATE_ALTCTL = 1 # Altitude control mode
+uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
+uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
+uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
+uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
+uint8 NAVIGATION_STATE_AUTO_RCRECOVER = 6 # RC recover mode
+uint8 NAVIGATION_STATE_AUTO_RTGS = 7 # Auto return to groundstation on data link loss
+uint8 NAVIGATION_STATE_AUTO_LANDENGFAIL = 8 # Auto land on engine failure
+uint8 NAVIGATION_STATE_AUTO_LANDGPSFAIL = 9 # Auto land on gps failure (e.g. open loop loiter down)
+uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
+uint8 NAVIGATION_STATE_LAND = 11 # Land mode
+uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
+uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
+uint8 NAVIGATION_STATE_OFFBOARD = 14
+uint8 NAVIGATION_STATE_MAX = 15
+
+# VEHICLE_MODE_FLAG, same as MAV_MODE_FLAG of MAVLink 1.0 protocol
+uint8 VEHICLE_MODE_FLAG_SAFETY_ARMED = 128
+uint8 VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64
+uint8 VEHICLE_MODE_FLAG_HIL_ENABLED = 32
+uint8 VEHICLE_MODE_FLAG_STABILIZED_ENABLED = 16
+uint8 VEHICLE_MODE_FLAG_GUIDED_ENABLED = 8
+uint8 VEHICLE_MODE_FLAG_AUTO_ENABLED = 4
+uint8 VEHICLE_MODE_FLAG_TEST_ENABLED = 2
+uint8 VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
+
+# VEHICLE_TYPE, should match 1:1 MAVLink's MAV_TYPE ENUM
+uint8 VEHICLE_TYPE_GENERIC = 0 # Generic micro air vehicle.
+uint8 VEHICLE_TYPE_FIXED_WING = 1 # Fixed wing aircraft.
+uint8 VEHICLE_TYPE_QUADROTOR = 2 # Quadrotor
+uint8 VEHICLE_TYPE_COAXIAL = 3 # Coaxial helicopter
+uint8 VEHICLE_TYPE_HELICOPTER = 4 # Normal helicopter with tail rotor.
+uint8 VEHICLE_TYPE_ANTENNA_TRACKER = 5 # Ground installation
+uint8 VEHICLE_TYPE_GCS = 6 # Operator control unit / ground control station
+uint8 VEHICLE_TYPE_AIRSHIP = 7 # Airship, controlled
+uint8 VEHICLE_TYPE_FREE_BALLOON = 8 # Free balloon, uncontrolled
+uint8 VEHICLE_TYPE_ROCKET = 9 # Rocket
+uint8 VEHICLE_TYPE_GROUND_ROVER = 10 # Ground rover
+uint8 VEHICLE_TYPE_SURFACE_BOAT = 11 # Surface vessel, boat, ship
+uint8 VEHICLE_TYPE_SUBMARINE = 12 # Submarine
+uint8 VEHICLE_TYPE_HEXAROTOR = 13 # Hexarotor
+uint8 VEHICLE_TYPE_OCTOROTOR = 14 # Octorotor
+uint8 VEHICLE_TYPE_TRICOPTER = 15 # Octorotor
+uint8 VEHICLE_TYPE_FLAPPING_WING = 16 # Flapping wing
+uint8 VEHICLE_TYPE_KITE = 17 # Kite
+uint8 VEHICLE_TYPE_ONBOARD_CONTROLLER=18 # Onboard companion controller
+uint8 VEHICLE_TYPE_VTOL_DUOROTOR = 19 # Vtol with two engines
+uint8 VEHICLE_TYPE_VTOL_QUADROTOR = 20 # Vtol with four engines*/
+uint8 VEHICLE_TYPE_ENUM_END = 21
+
+uint8 VEHICLE_BATTERY_WARNING_NONE = 0 # no battery low voltage warning active
+uint8 VEHICLE_BATTERY_WARNING_LOW = 1 # warning of low voltage
+uint8 VEHICLE_BATTERY_WARNING_CRITICAL = 2 # alerting of critical voltage
+
+# state machine / state of vehicle.
+# Encodes the complete system state and is set by the commander app.
+uint16 counter # incremented by the writing thread everytime new data is stored
+uint64 timestamp # in microseconds since system start, is set whenever the writing thread stores new data
+
+uint8 main_state # main state machine
+uint8 nav_state # set navigation state machine to specified value
+uint8 arming_state # current arming state
+uint8 hil_state # current hil state
+bool failsafe # true if system is in failsafe state
+
+int32 system_type # system type, inspired by MAVLink's VEHICLE_TYPE enum
+int32 system_id # system id, inspired by MAVLink's system ID field
+int32 component_id # subsystem / component id, inspired by MAVLink's component ID field
+
+bool is_rotary_wing # True if system is in rotary wing configuration, so for a VTOL this is only true while flying as a multicopter
+bool is_vtol # True if the system is VTOL capable
+
+bool condition_battery_voltage_valid
+bool condition_system_in_air_restore # true if we can restore in mid air
+bool condition_system_sensors_initialized
+bool condition_system_returned_to_home
+bool condition_auto_mission_available
+bool condition_global_position_valid # set to true by the commander app if the quality of the position estimate is good enough to use it for navigation
+bool condition_launch_position_valid # indicates a valid launch position
+bool condition_home_position_valid # indicates a valid home position (a valid home position is not always a valid launch)
+bool condition_local_position_valid
+bool condition_local_altitude_valid
+bool condition_airspeed_valid # set to true by the commander app if there is a valid airspeed measurement available
+bool condition_landed # true if vehicle is landed, always true if disarmed
+bool condition_power_input_valid # set if input power is valid
+float32 avionics_power_rail_voltage # voltage of the avionics power rail
+
+bool rc_signal_found_once
+bool rc_signal_lost # true if RC reception lost
+uint64 rc_signal_lost_timestamp # Time at which the RC reception was lost
+bool rc_signal_lost_cmd # true if RC lost mode is commanded
+bool rc_input_blocked # set if RC input should be ignored
+
+bool data_link_lost # datalink to GCS lost
+bool data_link_lost_cmd # datalink to GCS lost mode commanded
+uint8 data_link_lost_counter # counts unique data link lost events
+bool engine_failure # Set to true if an engine failure is detected
+bool engine_failure_cmd # Set to true if an engine failure mode is commanded
+bool gps_failure # Set to true if a gps failure is detected
+bool gps_failure_cmd # Set to true if a gps failure mode is commanded
+
+bool barometer_failure # Set to true if a barometer failure is detected
+
+bool offboard_control_signal_found_once
+bool offboard_control_signal_lost
+bool offboard_control_signal_weak
+uint64 offboard_control_signal_lost_interval # interval in microseconds without an offboard control message
+bool offboard_control_set_by_command # true if the offboard mode was set by a mavlink command and should not be overridden by RC
+
+# see SYS_STATUS mavlink message for the following
+uint32 onboard_control_sensors_present
+uint32 onboard_control_sensors_enabled
+uint32 onboard_control_sensors_health
+
+float32 load # processor load from 0 to 1
+float32 battery_voltage
+float32 battery_current
+float32 battery_remaining
+
+uint8 battery_warning # current battery warning mode, as defined by VEHICLE_BATTERY_WARNING enum
+uint16 drop_rate_comm
+uint16 errors_comm
+uint16 errors_count1
+uint16 errors_count2
+uint16 errors_count3
+uint16 errors_count4
+
+bool circuit_breaker_engaged_power_check
+bool circuit_breaker_engaged_airspd_check
+bool circuit_breaker_engaged_enginefailure_check
+bool circuit_breaker_engaged_gpsfailure_check