aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB/topics
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-28 09:54:11 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-28 09:54:11 +0200
commit13fc6703862862f4263d8d5d085b7a16b87190e1 (patch)
tree47f3a17cb6f38b1aafe22e1cdef085cd73cd3a1d /src/modules/uORB/topics
parentf57439b90e23de260259dec051d3e2ead2d61c8c (diff)
downloadpx4-firmware-13fc6703862862f4263d8d5d085b7a16b87190e1.tar.gz
px4-firmware-13fc6703862862f4263d8d5d085b7a16b87190e1.tar.bz2
px4-firmware-13fc6703862862f4263d8d5d085b7a16b87190e1.zip
Moved last libs, drivers and headers, cleaned up IO build
Diffstat (limited to 'src/modules/uORB/topics')
-rw-r--r--src/modules/uORB/topics/actuator_controls.h77
-rw-r--r--src/modules/uORB/topics/actuator_controls_effective.h70
-rw-r--r--src/modules/uORB/topics/actuator_outputs.h70
-rw-r--r--src/modules/uORB/topics/battery_status.h68
-rw-r--r--src/modules/uORB/topics/debug_key_value.h75
-rw-r--r--src/modules/uORB/topics/differential_pressure.h71
-rw-r--r--src/modules/uORB/topics/home_position.h77
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h88
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h94
-rw-r--r--src/modules/uORB/topics/omnidirectional_flow.h75
-rw-r--r--src/modules/uORB/topics/optical_flow.h77
-rw-r--r--src/modules/uORB/topics/parameter_update.h52
-rw-r--r--src/modules/uORB/topics/rc_channels.h108
-rw-r--r--src/modules/uORB/topics/sensor_combined.h115
-rw-r--r--src/modules/uORB/topics/subsystem_info.h97
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h90
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h78
-rw-r--r--src/modules/uORB/topics/vehicle_command.h140
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h86
-rw-r--r--src/modules/uORB/topics/vehicle_global_position_set_triplet.h78
-rw-r--r--src/modules/uORB/topics/vehicle_global_position_setpoint.h78
-rw-r--r--src/modules/uORB/topics/vehicle_gps_position.h100
-rw-r--r--src/modules/uORB/topics/vehicle_local_position.h87
-rw-r--r--src/modules/uORB/topics/vehicle_local_position_setpoint.h67
-rw-r--r--src/modules/uORB/topics/vehicle_rates_setpoint.h68
-rw-r--r--src/modules/uORB/topics/vehicle_status.h226
-rw-r--r--src/modules/uORB/topics/vehicle_vicon_position.h78
27 files changed, 2390 insertions, 0 deletions
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
new file mode 100644
index 000000000..0b50a29ac
--- /dev/null
+++ b/src/modules/uORB/topics/actuator_controls.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file actuator_controls.h
+ *
+ * Actuator control topics - mixer inputs.
+ *
+ * Values published to these topics are the outputs of the vehicle control
+ * system, and are expected to be mixed and used to drive the actuators
+ * (servos, speed controls, etc.) that operate the vehicle.
+ *
+ * Each topic can be published by a single controller
+ */
+
+#ifndef TOPIC_ACTUATOR_CONTROLS_H
+#define TOPIC_ACTUATOR_CONTROLS_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define NUM_ACTUATOR_CONTROLS 8
+#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
+
+struct actuator_controls_s {
+ uint64_t timestamp;
+ float control[NUM_ACTUATOR_CONTROLS];
+};
+
+/* actuator control sets; this list can be expanded as more controllers emerge */
+ORB_DECLARE(actuator_controls_0);
+ORB_DECLARE(actuator_controls_1);
+ORB_DECLARE(actuator_controls_2);
+ORB_DECLARE(actuator_controls_3);
+
+/* control sets with pre-defined applications */
+#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
+
+/** global 'actuator output is live' control. */
+struct actuator_armed_s {
+ bool armed; /**< Set to true if system is armed */
+ bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
+};
+
+ORB_DECLARE(actuator_armed);
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/actuator_controls_effective.h b/src/modules/uORB/topics/actuator_controls_effective.h
new file mode 100644
index 000000000..088c4fc8f
--- /dev/null
+++ b/src/modules/uORB/topics/actuator_controls_effective.h
@@ -0,0 +1,70 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file actuator_controls_effective.h
+ *
+ * Actuator control topics - mixer inputs.
+ *
+ * Values published to these topics are the outputs of the vehicle control
+ * system and mixing process; they are the control-scale values that are
+ * then fed to the actual actuator driver.
+ *
+ * Each topic can be published by a single controller
+ */
+
+#ifndef TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H
+#define TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H
+
+#include <stdint.h>
+#include "../uORB.h"
+#include "actuator_controls.h"
+
+#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
+#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
+
+struct actuator_controls_effective_s {
+ uint64_t timestamp;
+ float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
+};
+
+/* actuator control sets; this list can be expanded as more controllers emerge */
+ORB_DECLARE(actuator_controls_effective_0);
+ORB_DECLARE(actuator_controls_effective_1);
+ORB_DECLARE(actuator_controls_effective_2);
+ORB_DECLARE(actuator_controls_effective_3);
+
+/* control sets with pre-defined applications */
+#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS_EFFECTIVE ORB_ID(actuator_controls_effective_0)
+
+#endif /* TOPIC_ACTUATOR_CONTROLS_EFFECTIVE_H */ \ No newline at end of file
diff --git a/src/modules/uORB/topics/actuator_outputs.h b/src/modules/uORB/topics/actuator_outputs.h
new file mode 100644
index 000000000..bbe429073
--- /dev/null
+++ b/src/modules/uORB/topics/actuator_outputs.h
@@ -0,0 +1,70 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file actuator_outputs.h
+ *
+ * Actuator output values.
+ *
+ * Values published to these topics are the outputs of the control mixing
+ * system as sent to the actuators (servos, motors, etc.) that operate
+ * the vehicle.
+ *
+ * Each topic can be published by a single output driver.
+ */
+
+#ifndef TOPIC_ACTUATOR_OUTPUTS_H
+#define TOPIC_ACTUATOR_OUTPUTS_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define NUM_ACTUATOR_OUTPUTS 16
+#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
+
+struct actuator_outputs_s {
+ uint64_t timestamp; /**< output timestamp in us since system boot */
+ float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */
+ int noutputs; /**< valid outputs */
+};
+
+/* actuator output sets; this list can be expanded as more drivers emerge */
+ORB_DECLARE(actuator_outputs_0);
+ORB_DECLARE(actuator_outputs_1);
+ORB_DECLARE(actuator_outputs_2);
+ORB_DECLARE(actuator_outputs_3);
+
+/* output sets with pre-defined applications */
+#define ORB_ID_VEHICLE_CONTROLS ORB_ID(actuator_outputs_0)
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/battery_status.h b/src/modules/uORB/topics/battery_status.h
new file mode 100644
index 000000000..c40d0d4e5
--- /dev/null
+++ b/src/modules/uORB/topics/battery_status.h
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file battery_status.h
+ *
+ * Definition of the battery status uORB topic.
+ */
+
+#ifndef BATTERY_STATUS_H_
+#define BATTERY_STATUS_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Battery voltages and status
+ */
+struct battery_status_s {
+ uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
+ float voltage_v; /**< Battery voltage in volts, filtered */
+ float current_a; /**< Battery current in amperes, filtered, -1 if unknown */
+ float discharged_mah; /**< Discharged amount in mAh, filtered, -1 if unknown */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(battery_status);
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/debug_key_value.h b/src/modules/uORB/topics/debug_key_value.h
new file mode 100644
index 000000000..a9d1b83fd
--- /dev/null
+++ b/src/modules/uORB/topics/debug_key_value.h
@@ -0,0 +1,75 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file debug_key_value.h
+ * Definition of the debug named value uORB topic. Allows to send a 10-char key
+ * with a float as value.
+ */
+
+#ifndef TOPIC_DEBUG_KEY_VALUE_H_
+#define TOPIC_DEBUG_KEY_VALUE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ */
+
+/**
+ * Key/value pair for debugging
+ */
+struct debug_key_value_s {
+
+ /*
+ * Actual data, this is specific to the type of data which is stored in this struct
+ * A line containing L0GME will be added by the Python logging code generator to the
+ * logged dataset.
+ */
+ uint32_t timestamp_ms; /**< in milliseconds since system start */
+ char key[10]; /**< max. 10 characters as key / name */
+ float value; /**< the value to send as debug output */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(debug_key_value);
+
+#endif
diff --git a/src/modules/uORB/topics/differential_pressure.h b/src/modules/uORB/topics/differential_pressure.h
new file mode 100644
index 000000000..d5e4bf37e
--- /dev/null
+++ b/src/modules/uORB/topics/differential_pressure.h
@@ -0,0 +1,71 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file differential_pressure.h
+ *
+ * Definition of differential pressure topic
+ */
+
+#ifndef TOPIC_DIFFERENTIAL_PRESSURE_H_
+#define TOPIC_DIFFERENTIAL_PRESSURE_H_
+
+#include "../uORB.h"
+#include <stdint.h>
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Differential pressure and airspeed
+ */
+struct differential_pressure_s {
+ uint64_t timestamp; /**< microseconds since system boot, needed to integrate */
+ float static_pressure_mbar; /**< Static / environment pressure */
+ float differential_pressure_mbar; /**< Differential pressure reading */
+ float temperature_celcius; /**< ambient temperature in celcius, -1 if unknown */
+ float indicated_airspeed_m_s; /**< indicated airspeed in meters per second, -1 if unknown */
+ float true_airspeed_m_s; /**< true airspeed in meters per second, -1 if unknown */
+ float voltage; /**< Voltage from the airspeed sensor (voltage divider already compensated) */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(differential_pressure);
+
+#endif
diff --git a/src/modules/uORB/topics/home_position.h b/src/modules/uORB/topics/home_position.h
new file mode 100644
index 000000000..7e1b82a0f
--- /dev/null
+++ b/src/modules/uORB/topics/home_position.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012-2013 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file home_position.h
+ * Definition of the GPS home position uORB topic.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#ifndef TOPIC_HOME_POSITION_H_
+#define TOPIC_HOME_POSITION_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * GPS home position in WGS84 coordinates.
+ */
+struct home_position_s
+{
+ uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
+ uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp from the gps module */
+
+ int32_t lat; /**< Latitude in 1E7 degrees */
+ int32_t lon; /**< Longitude in 1E7 degrees */
+ int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
+ float eph_m; /**< GPS HDOP horizontal dilution of position in m */
+ float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+ float s_variance_m_s; /**< speed accuracy estimate m/s */
+ float p_variance_m; /**< position accuracy estimate m */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(home_position);
+
+#endif
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
new file mode 100644
index 000000000..261a8a4ad
--- /dev/null
+++ b/src/modules/uORB/topics/manual_control_setpoint.h
@@ -0,0 +1,88 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file manual_control_setpoint.h
+ * Definition of the manual_control_setpoint uORB topic.
+ */
+
+#ifndef TOPIC_MANUAL_CONTROL_SETPOINT_H_
+#define TOPIC_MANUAL_CONTROL_SETPOINT_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct manual_control_setpoint_s {
+ uint64_t timestamp;
+
+ float roll; /**< ailerons roll / roll rate input */
+ float pitch; /**< elevator / pitch / pitch rate */
+ float yaw; /**< rudder / yaw rate / yaw */
+ float throttle; /**< throttle / collective thrust / altitude */
+
+ float manual_override_switch; /**< manual override mode (mandatory) */
+ float auto_mode_switch; /**< auto mode switch (mandatory) */
+
+ /**
+ * Any of the channels below may not be available and be set to NaN
+ * to indicate that it does not contain valid data.
+ */
+ float manual_mode_switch; /**< manual mode (man, sas, alt) switch (optional) */
+ float manual_sas_switch; /**< sas mode (rates / attitude) switch (optional) */
+ float return_to_launch_switch; /**< return to launch switch (0 = disabled, 1 = enabled) */
+ float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */
+
+ float flaps; /**< flap position */
+
+ float aux1; /**< default function: camera yaw / azimuth */
+ float aux2; /**< default function: camera pitch / tilt */
+ float aux3; /**< default function: camera trigger */
+ float aux4; /**< default function: camera roll */
+ float aux5; /**< default function: payload drop */
+
+}; /**< manual control inputs */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(manual_control_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
new file mode 100644
index 000000000..2e895c59c
--- /dev/null
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -0,0 +1,94 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file offboard_control_setpoint.h
+ * Definition of the manual_control_setpoint uORB topic.
+ */
+
+#ifndef TOPIC_OFFBOARD_CONTROL_SETPOINT_H_
+#define TOPIC_OFFBOARD_CONTROL_SETPOINT_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Off-board control inputs.
+ *
+ * Typically sent by a ground control station / joystick or by
+ * some off-board controller via C or SIMULINK.
+ */
+enum OFFBOARD_CONTROL_MODE
+{
+ OFFBOARD_CONTROL_MODE_DIRECT = 0,
+ OFFBOARD_CONTROL_MODE_DIRECT_RATES = 1,
+ OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE = 2,
+ OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY = 3,
+ OFFBOARD_CONTROL_MODE_DIRECT_POSITION = 4,
+ OFFBOARD_CONTROL_MODE_ATT_YAW_RATE = 5,
+ OFFBOARD_CONTROL_MODE_ATT_YAW_POS = 6,
+ OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
+};
+
+struct offboard_control_setpoint_s {
+ uint64_t timestamp;
+
+ enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */
+ bool armed; /**< Armed flag set, yes / no */
+ float p1; /**< ailerons roll / roll rate input */
+ float p2; /**< elevator / pitch / pitch rate */
+ float p3; /**< rudder / yaw rate / yaw */
+ float p4; /**< throttle / collective thrust / altitude */
+
+ float override_mode_switch;
+
+ float aux1_cam_pan_flaps;
+ float aux2_cam_tilt;
+ float aux3_cam_zoom;
+ float aux4_cam_roll;
+
+}; /**< offboard control inputs */
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(offboard_control_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/omnidirectional_flow.h b/src/modules/uORB/topics/omnidirectional_flow.h
new file mode 100644
index 000000000..8f4be3b3f
--- /dev/null
+++ b/src/modules/uORB/topics/omnidirectional_flow.h
@@ -0,0 +1,75 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file optical_flow.h
+ * Definition of the optical flow uORB topic.
+ */
+
+#ifndef TOPIC_OMNIDIRECTIONAL_FLOW_H_
+#define TOPIC_OMNIDIRECTIONAL_FLOW_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ */
+
+/**
+ * Omnidirectional optical flow in NED body frame in SI units.
+ *
+ * @see http://en.wikipedia.org/wiki/International_System_of_Units
+ */
+struct omnidirectional_flow_s {
+
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ uint16_t left[10]; /**< Left flow, in decipixels */
+ uint16_t right[10]; /**< Right flow, in decipixels */
+ float front_distance_m; /**< Altitude / distance to object front in meters */
+ uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
+ uint8_t sensor_id; /**< id of the sensor emitting the flow value */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(omnidirectional_flow);
+
+#endif
diff --git a/src/modules/uORB/topics/optical_flow.h b/src/modules/uORB/topics/optical_flow.h
new file mode 100644
index 000000000..c854f0079
--- /dev/null
+++ b/src/modules/uORB/topics/optical_flow.h
@@ -0,0 +1,77 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file optical_flow.h
+ * Definition of the optical flow uORB topic.
+ */
+
+#ifndef TOPIC_OPTICAL_FLOW_H_
+#define TOPIC_OPTICAL_FLOW_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ */
+
+/**
+ * Optical flow in NED body frame in SI units.
+ *
+ * @see http://en.wikipedia.org/wiki/International_System_of_Units
+ */
+struct optical_flow_s {
+
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ uint16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */
+ uint16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */
+ float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */
+ float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */
+ float ground_distance_m; /**< Altitude / distance to ground in meters */
+ uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */
+ uint8_t sensor_id; /**< id of the sensor emitting the flow value */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(optical_flow);
+
+#endif
diff --git a/src/modules/uORB/topics/parameter_update.h b/src/modules/uORB/topics/parameter_update.h
new file mode 100644
index 000000000..300e895c7
--- /dev/null
+++ b/src/modules/uORB/topics/parameter_update.h
@@ -0,0 +1,52 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file parameter_update.h
+ * Notification about a parameter update.
+ */
+
+#ifndef TOPIC_PARAMETER_UPDATE_H
+#define TOPIC_PARAMETER_UPDATE_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+struct parameter_update_s {
+ /** time at which the latest parameter was updated */
+ uint64_t timestamp;
+};
+
+ORB_DECLARE(parameter_update);
+
+#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
new file mode 100644
index 000000000..9dd54df91
--- /dev/null
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Nils Wenzler <wenzlern@student.ethz.ch>
+ * @author Ivan Ovinnikov <oivan@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file rc_channels.h
+ * Definition of the rc_channels uORB topic.
+ */
+
+#ifndef RC_CHANNELS_H_
+#define RC_CHANNELS_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * The number of RC channel inputs supported.
+ * Current (Q1/2013) radios support up to 18 channels,
+ * leaving at a sane value of 14.
+ */
+#define RC_CHANNELS_MAX 14
+
+/**
+ * This defines the mapping of the RC functions.
+ * The value assigned to the specific function corresponds to the entry of
+ * the channel array chan[].
+ */
+enum RC_CHANNELS_FUNCTION
+{
+ THROTTLE = 0,
+ ROLL = 1,
+ PITCH = 2,
+ YAW = 3,
+ OVERRIDE = 4,
+ AUTO_MODE = 5,
+ MANUAL_MODE = 6,
+ SAS_MODE = 7,
+ RTL = 8,
+ OFFBOARD_MODE = 9,
+ FLAPS = 10,
+ AUX_1 = 11,
+ AUX_2 = 12,
+ AUX_3 = 13,
+ AUX_4 = 14,
+ AUX_5 = 15,
+ RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
+};
+
+struct rc_channels_s {
+
+ uint64_t timestamp; /**< In microseconds since boot time. */
+ uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
+ struct {
+ float scaled; /**< Scaled to -1..1 (throttle: 0..1) */
+ } chan[RC_CHANNELS_MAX];
+ uint8_t chan_count; /**< number of valid channels */
+
+ /*String array to store the names of the functions*/
+ char function_name[RC_CHANNELS_FUNCTION_MAX][20];
+ int8_t function[RC_CHANNELS_FUNCTION_MAX];
+ uint8_t rssi; /**< Overall receive signal strength */
+}; /**< radio control channels. */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(rc_channels);
+
+#endif
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
new file mode 100644
index 000000000..961ee8b4a
--- /dev/null
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -0,0 +1,115 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file sensor_combined.h
+ * Definition of the sensor_combined uORB topic.
+ */
+
+#ifndef SENSOR_COMBINED_H_
+#define SENSOR_COMBINED_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+enum MAGNETOMETER_MODE {
+ MAGNETOMETER_MODE_NORMAL = 0,
+ MAGNETOMETER_MODE_POSITIVE_BIAS,
+ MAGNETOMETER_MODE_NEGATIVE_BIAS
+};
+
+/**
+ * Sensor readings in raw and SI-unit form.
+ *
+ * These values are read from the sensors. Raw values are in sensor-specific units,
+ * the scaled values are in SI-units, as visible from the ending of the variable
+ * or the comments. The use of the SI fields is in general advised, as these fields
+ * are scaled and offset-compensated where possible and do not change with board
+ * revisions and sensor updates.
+ *
+ */
+struct sensor_combined_s {
+
+ /*
+ * Actual data, this is specific to the type of data which is stored in this struct
+ * A line containing L0GME will be added by the Python logging code generator to the
+ * logged dataset.
+ */
+
+ /* NOTE: Ordering of fields optimized to align to 32 bit / 4 bytes Change with consideration only */
+
+ uint64_t timestamp; /**< Timestamp in microseconds since boot */
+
+ int16_t gyro_raw[3]; /**< Raw sensor values of angular velocity */
+ uint16_t gyro_counter; /**< Number of raw measurments taken */
+ float gyro_rad_s[3]; /**< Angular velocity in radian per seconds */
+
+ int16_t accelerometer_raw[3]; /**< Raw acceleration in NED body frame */
+ uint32_t accelerometer_counter; /**< Number of raw acc measurements taken */
+ float accelerometer_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */
+ int accelerometer_mode; /**< Accelerometer measurement mode */
+ float accelerometer_range_m_s2; /**< Accelerometer measurement range in m/s^2 */
+
+ int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame */
+ float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss */
+ int magnetometer_mode; /**< Magnetometer measurement mode */
+ float magnetometer_range_ga; /**< ± measurement range in Gauss */
+ float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */
+ uint32_t magnetometer_counter; /**< Number of raw mag measurements taken */
+
+ float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */
+ float baro_alt_meter; /**< Altitude, already temp. comp. */
+ float baro_temp_celcius; /**< Temperature in degrees celsius */
+ float adc_voltage_v[4]; /**< ADC voltages of ADC Chan 10/11/12/13 or -1 */
+ float mcu_temp_celcius; /**< Internal temperature measurement of MCU */
+ uint32_t baro_counter; /**< Number of raw baro measurements taken */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(sensor_combined);
+
+#endif
diff --git a/src/modules/uORB/topics/subsystem_info.h b/src/modules/uORB/topics/subsystem_info.h
new file mode 100644
index 000000000..c415e832e
--- /dev/null
+++ b/src/modules/uORB/topics/subsystem_info.h
@@ -0,0 +1,97 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file subsystem_info.h
+ * Definition of the subsystem info topic.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ */
+
+#ifndef TOPIC_SUBSYSTEM_INFO_H_
+#define TOPIC_SUBSYSTEM_INFO_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ */
+
+enum SUBSYSTEM_TYPE
+{
+ SUBSYSTEM_TYPE_GYRO = 1,
+ SUBSYSTEM_TYPE_ACC = 2,
+ SUBSYSTEM_TYPE_MAG = 4,
+ SUBSYSTEM_TYPE_ABSPRESSURE = 8,
+ SUBSYSTEM_TYPE_DIFFPRESSURE = 16,
+ SUBSYSTEM_TYPE_GPS = 32,
+ SUBSYSTEM_TYPE_OPTICALFLOW = 64,
+ SUBSYSTEM_TYPE_CVPOSITION = 128,
+ SUBSYSTEM_TYPE_LASERPOSITION = 256,
+ SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 512,
+ SUBSYSTEM_TYPE_ANGULARRATECONTROL = 1024,
+ SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 2048,
+ SUBSYSTEM_TYPE_YAWPOSITION = 4096,
+ SUBSYSTEM_TYPE_ALTITUDECONTROL = 16384,
+ SUBSYSTEM_TYPE_POSITIONCONTROL = 32768,
+ SUBSYSTEM_TYPE_MOTORCONTROL = 65536,
+ SUBSYSTEM_TYPE_RANGEFINDER = 131072
+};
+
+/**
+ * State of individual sub systems
+ */
+struct subsystem_info_s {
+ bool present;
+ bool enabled;
+ bool ok;
+
+ enum SUBSYSTEM_TYPE subsystem_type;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(subsystem_info);
+
+#endif /* TOPIC_SUBSYSTEM_INFO_H_ */
+
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
new file mode 100755
index 000000000..c31c81d0c
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_attitude.h
@@ -0,0 +1,90 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_attitude.h
+ * Definition of the attitude uORB topic.
+ */
+
+#ifndef VEHICLE_ATTITUDE_H_
+#define VEHICLE_ATTITUDE_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ */
+
+/**
+ * Attitude in NED body frame in SI units.
+ *
+ * @see http://en.wikipedia.org/wiki/International_System_of_Units
+ */
+struct vehicle_attitude_s {
+
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ /* This is similar to the mavlink message ATTITUDE, but for onboard use */
+
+ /** @warning roll, pitch and yaw have always to be valid, the rotation matrix and quaternion are optional */
+
+ float roll; /**< Roll angle (rad, Tait-Bryan, NED) */
+ float pitch; /**< Pitch angle (rad, Tait-Bryan, NED) */
+ float yaw; /**< Yaw angle (rad, Tait-Bryan, NED) */
+ float rollspeed; /**< Roll angular speed (rad/s, Tait-Bryan, NED) */
+ float pitchspeed; /**< Pitch angular speed (rad/s, Tait-Bryan, NED) */
+ float yawspeed; /**< Yaw angular speed (rad/s, Tait-Bryan, NED) */
+ float rollacc; /**< Roll angular accelration (rad/s, Tait-Bryan, NED) */
+ float pitchacc; /**< Pitch angular acceleration (rad/s, Tait-Bryan, NED) */
+ float yawacc; /**< Yaw angular acceleration (rad/s, Tait-Bryan, NED) */
+ float rate_offsets[3]; /**< Offsets of the body angular rates from zero */
+ float R[3][3]; /**< Rotation matrix body to world, (Tait-Bryan, NED) */
+ float q[4]; /**< Quaternion (NED) */
+ bool R_valid; /**< Rotation matrix valid */
+ bool q_valid; /**< Quaternion valid */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_attitude);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
new file mode 100644
index 000000000..a7cda34a8
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
@@ -0,0 +1,78 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_attitude_setpoint.h
+ * Definition of the vehicle attitude setpoint uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_ATTITUDE_SETPOINT_H_
+#define TOPIC_VEHICLE_ATTITUDE_SETPOINT_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * vehicle attitude setpoint.
+ */
+struct vehicle_attitude_setpoint_s
+{
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+
+ float roll_body; /**< body angle in NED frame */
+ float pitch_body; /**< body angle in NED frame */
+ float yaw_body; /**< body angle in NED frame */
+ //float body_valid; /**< Set to true if body angles are valid */
+
+ float R_body[9]; /**< Rotation matrix describing the setpoint as rotation from the current body frame */
+ bool R_valid; /**< Set to true if rotation matrix is valid */
+
+ float thrust; /**< Thrust in Newton the power system should generate */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_attitude_setpoint);
+
+#endif /* TOPIC_ARDRONE_CONTROL_H_ */
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
new file mode 100644
index 000000000..fac571659
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -0,0 +1,140 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2008-2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_command.h
+ * Definition of the vehicle command uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_COMMAND_H_
+#define TOPIC_VEHICLE_COMMAND_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Commands for commander app.
+ *
+ * Should contain all commands from MAVLink's VEHICLE_CMD ENUM,
+ * but can contain additional ones.
+ */
+enum VEHICLE_CMD
+{
+ VEHICLE_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ VEHICLE_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ VEHICLE_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
+ VEHICLE_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
+ VEHICLE_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
+ VEHICLE_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ VEHICLE_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ VEHICLE_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */
+ VEHICLE_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
+ VEHICLE_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
+ VEHICLE_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
+ VEHICLE_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
+ VEHICLE_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
+ VEHICLE_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
+ VEHICLE_CMD_ENUM_END=401, /* | */
+};
+
+/**
+ * Commands for commander app.
+ *
+ * Should contain all of MAVLink's VEHICLE_CMD_RESULT values
+ * but can contain additional ones.
+ */
+enum VEHICLE_CMD_RESULT
+{
+ VEHICLE_CMD_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
+ VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
+ VEHICLE_CMD_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
+ VEHICLE_CMD_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
+ VEHICLE_CMD_RESULT_FAILED=4, /* Command executed, but failed | */
+ VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
+};
+
+
+struct vehicle_command_s
+{
+ float param1; /**< Parameter 1, as defined by MAVLink VEHICLE_CMD enum. */
+ float param2; /**< Parameter 2, as defined by MAVLink VEHICLE_CMD enum. */
+ float param3; /**< Parameter 3, as defined by MAVLink VEHICLE_CMD enum. */
+ float param4; /**< Parameter 4, as defined by MAVLink VEHICLE_CMD enum. */
+ float param5; /**< Parameter 5, as defined by MAVLink VEHICLE_CMD enum. */
+ float param6; /**< Parameter 6, as defined by MAVLink VEHICLE_CMD enum. */
+ float param7; /**< Parameter 7, as defined by MAVLink VEHICLE_CMD enum. */
+ uint16_t command; /**< Command ID, as defined MAVLink by VEHICLE_CMD enum. */
+ uint8_t target_system; /**< System which should execute the command */
+ uint8_t target_component; /**< Component which should execute the command, 0 for all components */
+ uint8_t source_system; /**< System sending the command */
+ uint8_t source_component; /**< Component sending the command */
+ uint8_t confirmation; /**< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) */
+}; /**< command sent to vehicle */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_command);
+
+
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
new file mode 100644
index 000000000..f036c7223
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -0,0 +1,86 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_global_position.h
+ * Definition of the global fused WGS84 position uORB topic.
+ */
+
+#ifndef VEHICLE_GLOBAL_POSITION_T_H_
+#define VEHICLE_GLOBAL_POSITION_T_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+ /**
+ * Fused global position in WGS84.
+ *
+ * This struct contains the system's believ about its position. It is not the raw GPS
+ * measurement (@see vehicle_gps_position). This topic is usually published by the position
+ * estimator, which will take more sources of information into account than just GPS,
+ * e.g. control inputs of the vehicle in a Kalman-filter implementation.
+ */
+struct vehicle_global_position_s
+{
+ uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
+ uint64_t time_gps_usec; /**< GPS timestamp in microseconds */
+ bool valid; /**< true if position satisfies validity criteria of estimator */
+
+ int32_t lat; /**< Latitude in 1E7 degrees LOGME */
+ int32_t lon; /**< Longitude in 1E7 degrees LOGME */
+ float alt; /**< Altitude in meters LOGME */
+ float relative_alt; /**< Altitude above home position in meters, LOGME */
+ float vx; /**< Ground X Speed (Latitude), m/s in ENU LOGME */
+ float vy; /**< Ground Y Speed (Longitude), m/s in ENU LOGME */
+ float vz; /**< Ground Z Speed (Altitude), m/s in ENU LOGME */
+ float hdg; /**< Compass heading in radians -PI..+PI. */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_global_position);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
new file mode 100644
index 000000000..318abba89
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
@@ -0,0 +1,78 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_global_position_setpoint.h
+ * Definition of the global WGS84 position setpoint uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
+#define TOPIC_VEHICLE_GLOBAL_POSITION_SET_TRIPLET_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+#include "vehicle_global_position_setpoint.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Global position setpoint triplet in WGS84 coordinates.
+ *
+ * This are the three next waypoints (or just the next two or one).
+ */
+struct vehicle_global_position_set_triplet_s
+{
+ bool previous_valid;
+ bool next_valid;
+
+ struct vehicle_global_position_setpoint_s previous;
+ struct vehicle_global_position_setpoint_s current;
+ struct vehicle_global_position_setpoint_s next;
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_global_position_set_triplet);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position_setpoint.h b/src/modules/uORB/topics/vehicle_global_position_setpoint.h
new file mode 100644
index 000000000..eec6a8229
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_global_position_setpoint.h
@@ -0,0 +1,78 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_global_position_setpoint.h
+ * Definition of the global WGS84 position setpoint uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_GLOBAL_POSITION_SETPOINT_H_
+#define TOPIC_VEHICLE_GLOBAL_POSITION_SETPOINT_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Global position setpoint in WGS84 coordinates.
+ *
+ * This is the position the MAV is heading towards. If it of type loiter,
+ * the MAV is circling around it with the given loiter radius in meters.
+ */
+struct vehicle_global_position_setpoint_s
+{
+ bool altitude_is_relative; /**< true if altitude is relative from start point */
+ int32_t lat; /**< latitude in degrees * 1E7 */
+ int32_t lon; /**< longitude in degrees * 1E7 */
+ float altitude; /**< altitude in meters */
+ float yaw; /**< in radians NED -PI..+PI */
+ float loiter_radius; /**< loiter radius in meters, 0 for a VTOL to hover */
+ bool is_loiter; /**< true if loitering is enabled */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_global_position_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h
new file mode 100644
index 000000000..0a7fb4e9d
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_gps_position.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_gps_position.h
+ * Definition of the GPS WGS84 uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_GPS_H_
+#define TOPIC_VEHICLE_GPS_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * GPS position in WGS84 coordinates.
+ */
+struct vehicle_gps_position_s
+{
+ uint64_t timestamp_position; /**< Timestamp for position information */
+ int32_t lat; /**< Latitude in 1E7 degrees */
+ int32_t lon; /**< Longitude in 1E7 degrees */
+ int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL */
+
+ uint64_t timestamp_variance;
+ float s_variance_m_s; /**< speed accuracy estimate m/s */
+ float p_variance_m; /**< position accuracy estimate m */
+ float c_variance_rad; /**< course accuracy estimate rad */
+ uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */
+
+ float eph_m; /**< GPS HDOP horizontal dilution of position in m */
+ float epv_m; /**< GPS VDOP horizontal dilution of position in m */
+
+ uint64_t timestamp_velocity; /**< Timestamp for velocity informations */
+ float vel_m_s; /**< GPS ground speed (m/s) */
+ float vel_n_m_s; /**< GPS ground speed in m/s */
+ float vel_e_m_s; /**< GPS ground speed in m/s */
+ float vel_d_m_s; /**< GPS ground speed in m/s */
+ float cog_rad; /**< Course over ground (NOT heading, but direction of movement) in rad, -PI..PI */
+ bool vel_ned_valid; /**< Flag to indicate if NED speed is valid */
+
+ uint64_t timestamp_time; /**< Timestamp for time information */
+ uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
+
+ uint64_t timestamp_satellites; /**< Timestamp for sattelite information */
+ uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */
+ uint8_t satellite_prn[20]; /**< Global satellite ID */
+ uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */
+ uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */
+ uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */
+ uint8_t satellite_snr[20]; /**< Signal to noise ratio of satellite */
+ bool satellite_info_available; /**< 0 for no info, 1 for info available */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_gps_position);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_local_position.h b/src/modules/uORB/topics/vehicle_local_position.h
new file mode 100644
index 000000000..76eddeacd
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_local_position.h
@@ -0,0 +1,87 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_local_position.h
+ * Definition of the local fused NED position uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_LOCAL_POSITION_H_
+#define TOPIC_VEHICLE_LOCAL_POSITION_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Fused local position in NED.
+ */
+struct vehicle_local_position_s
+{
+ uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
+ bool valid; /**< true if position satisfies validity criteria of estimator */
+
+ float x; /**< X positin in meters in NED earth-fixed frame */
+ float y; /**< X positin in meters in NED earth-fixed frame */
+ float z; /**< Z positin in meters in NED earth-fixed frame (negative altitude) */
+ float absolute_alt; /**< Altitude as defined by pressure / GPS, LOGME */
+ float vx; /**< Ground X Speed (Latitude), m/s in NED LOGME */
+ float vy; /**< Ground Y Speed (Longitude), m/s in NED LOGME */
+ float vz; /**< Ground Z Speed (Altitude), m/s in NED LOGME */
+ float hdg; /**< Compass heading in radians -PI..+PI. */
+
+ // TODO Add covariances here
+
+ /* Reference position in GPS / WGS84 frame */
+ uint64_t home_timestamp;/**< Time when home position was set */
+ int32_t home_lat; /**< Latitude in 1E7 degrees LOGME */
+ int32_t home_lon; /**< Longitude in 1E7 degrees LOGME */
+ float home_alt; /**< Altitude in meters LOGME */
+ float home_hdg; /**< Compass heading in radians -PI..+PI. */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_local_position);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_local_position_setpoint.h b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
new file mode 100644
index 000000000..d24d81e3a
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_local_position_setpoint.h
@@ -0,0 +1,67 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_local_position_setpoint.h
+ * Definition of the local NED position setpoint uORB topic.
+ */
+
+#ifndef TOPIC_VEHICLE_LOCAL_POSITION_SETPOINT_H_
+#define TOPIC_VEHICLE_LOCAL_POSITION_SETPOINT_H_
+
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct vehicle_local_position_setpoint_s
+{
+ float x; /**< in meters NED */
+ float y; /**< in meters NED */
+ float z; /**< in meters NED */
+ float yaw; /**< in radians NED -PI..+PI */
+}; /**< Local position in NED frame to go to */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_local_position_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_rates_setpoint.h b/src/modules/uORB/topics/vehicle_rates_setpoint.h
new file mode 100644
index 000000000..46e62c4b7
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_rates_setpoint.h
@@ -0,0 +1,68 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_rates_setpoint.h
+ * Definition of the vehicle rates setpoint topic
+ */
+
+#ifndef TOPIC_VEHICLE_RATES_SETPOINT_H_
+#define TOPIC_VEHICLE_RATES_SETPOINT_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+struct vehicle_rates_setpoint_s
+{
+ uint64_t timestamp; /**< in microseconds since system start */
+
+ float roll; /**< body angular rates in NED frame */
+ float pitch; /**< body angular rates in NED frame */
+ float yaw; /**< body angular rates in NED frame */
+ float thrust; /**< thrust normalized to 0..1 */
+
+}; /**< vehicle_rates_setpoint */
+
+ /**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_rates_setpoint);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
new file mode 100644
index 000000000..c7c1048f6
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -0,0 +1,226 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Petri Tanskanen <petri.tanskanen@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_status.h
+ * Definition of the vehicle_status uORB topic.
+ *
+ * Published the state machine and the system status bitfields
+ * (see SYS_STATUS mavlink message), published only by commander app.
+ *
+ * All apps should write to subsystem_info:
+ *
+ * (any app) --> subsystem_info (published) --> (commander app state machine) --> vehicle_status --> (mavlink app)
+ */
+
+#ifndef VEHICLE_STATUS_H_
+#define VEHICLE_STATUS_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics @{
+ */
+
+/* State Machine */
+typedef enum
+{
+ SYSTEM_STATE_PREFLIGHT = 0,
+ SYSTEM_STATE_STANDBY = 1,
+ SYSTEM_STATE_GROUND_READY = 2,
+ SYSTEM_STATE_MANUAL = 3,
+ SYSTEM_STATE_STABILIZED = 4,
+ SYSTEM_STATE_AUTO = 5,
+ SYSTEM_STATE_MISSION_ABORT = 6,
+ SYSTEM_STATE_EMCY_LANDING = 7,
+ SYSTEM_STATE_EMCY_CUTOFF = 8,
+ SYSTEM_STATE_GROUND_ERROR = 9,
+ SYSTEM_STATE_REBOOT= 10,
+
+} commander_state_machine_t;
+
+enum VEHICLE_MODE_FLAG {
+ VEHICLE_MODE_FLAG_SAFETY_ARMED = 128,
+ VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64,
+ VEHICLE_MODE_FLAG_HIL_ENABLED = 32,
+ VEHICLE_MODE_FLAG_STABILIZED_ENABLED = 16,
+ VEHICLE_MODE_FLAG_GUIDED_ENABLED = 8,
+ VEHICLE_MODE_FLAG_AUTO_ENABLED = 4,
+ VEHICLE_MODE_FLAG_TEST_ENABLED = 2,
+ VEHICLE_MODE_FLAG_CUSTOM_MODE_ENABLED = 1
+}; /**< Same as MAV_MODE_FLAG of MAVLink 1.0 protocol */
+
+enum VEHICLE_FLIGHT_MODE {
+ VEHICLE_FLIGHT_MODE_MANUAL = 0, /**< direct manual control, exact mode determined by VEHICLE_MANUAL_CONTROL_MODE */
+ VEHICLE_FLIGHT_MODE_STAB, /**< attitude or rate stabilization plus velocity or position stabilization */
+ VEHICLE_FLIGHT_MODE_HOLD, /**< hold current position (hover or loiter around position when switched) */
+ VEHICLE_FLIGHT_MODE_AUTO /**< attitude or rate stabilization plus absolute position control and waypoints */
+};
+
+enum VEHICLE_MANUAL_CONTROL_MODE {
+ VEHICLE_MANUAL_CONTROL_MODE_DIRECT = 0, /**< no attitude control, direct stick input mixing (only fixed wing) */
+ VEHICLE_MANUAL_CONTROL_MODE_RATES, /**< body rates control mode */
+ VEHICLE_MANUAL_CONTROL_MODE_SAS /**< stability augmented system (SAS) mode */
+};
+
+enum VEHICLE_MANUAL_SAS_MODE {
+ VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_ABS = 0, /**< roll, pitch and yaw absolute */
+ VEHICLE_MANUAL_SAS_MODE_ROLL_PITCH_ABS_YAW_RATE, /**< roll and pitch absolute, yaw rate */
+ VEHICLE_MANUAL_SAS_MODE_SIMPLE, /**< simple mode (includes altitude hold) */
+ VEHICLE_MANUAL_SAS_MODE_ALTITUDE /**< altitude hold */
+};
+
+/**
+ * Should match 1:1 MAVLink's MAV_TYPE ENUM
+ */
+enum VEHICLE_TYPE {
+ VEHICLE_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
+ VEHICLE_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
+ VEHICLE_TYPE_QUADROTOR=2, /* Quadrotor | */
+ VEHICLE_TYPE_COAXIAL=3, /* Coaxial helicopter | */
+ VEHICLE_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
+ VEHICLE_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
+ VEHICLE_TYPE_GCS=6, /* Operator control unit / ground control station | */
+ VEHICLE_TYPE_AIRSHIP=7, /* Airship, controlled | */
+ VEHICLE_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
+ VEHICLE_TYPE_ROCKET=9, /* Rocket | */
+ VEHICLE_TYPE_GROUND_ROVER=10, /* Ground rover | */
+ VEHICLE_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
+ VEHICLE_TYPE_SUBMARINE=12, /* Submarine | */
+ VEHICLE_TYPE_HEXAROTOR=13, /* Hexarotor | */
+ VEHICLE_TYPE_OCTOROTOR=14, /* Octorotor | */
+ VEHICLE_TYPE_TRICOPTER=15, /* Octorotor | */
+ VEHICLE_TYPE_FLAPPING_WING=16, /* Flapping wing | */
+ VEHICLE_TYPE_KITE=17, /* Kite | */
+ VEHICLE_TYPE_ENUM_END=18, /* | */
+};
+
+enum VEHICLE_BATTERY_WARNING {
+ VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
+ VEHICLE_BATTERY_WARNING_WARNING, /**< warning of low voltage 1. stage */
+ VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
+};
+
+
+/**
+ * state machine / state of vehicle.
+ *
+ * Encodes the complete system state and is set by the commander app.
+ */
+struct vehicle_status_s
+{
+ /* use of a counter and timestamp recommended (but not necessary) */
+
+ uint16_t counter; /**< incremented by the writing thread everytime new data is stored */
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
+ uint64_t failsave_lowlevel_start_time; /**< time when the lowlevel failsafe flag was set */
+ //uint64_t failsave_highlevel_begin; TO BE COMPLETED
+
+ commander_state_machine_t state_machine; /**< current flight state, main state machine */
+ enum VEHICLE_FLIGHT_MODE flight_mode; /**< current flight mode, as defined by mode switch */
+ enum VEHICLE_MANUAL_CONTROL_MODE manual_control_mode; /**< current attitude control mode, as defined by VEHICLE_ATTITUDE_MODE enum */
+ enum VEHICLE_MANUAL_SAS_MODE manual_sas_mode; /**< current stabilization mode */
+ int32_t system_type; /**< system type, inspired by MAVLink's VEHICLE_TYPE enum */
+ int32_t system_id; /**< system id, inspired by MAVLink's system ID field */
+ int32_t component_id; /**< subsystem / component id, inspired by MAVLink's component ID field */
+
+ /* system flags - these represent the state predicates */
+
+ bool flag_system_armed; /**< true is motors / actuators are armed */
+ bool flag_control_manual_enabled; /**< true if manual input is mixed in */
+ bool flag_control_offboard_enabled; /**< true if offboard control input is on */
+ bool flag_hil_enabled; /**< true if hardware in the loop simulation is enabled */
+
+ 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_velocity_enabled; /**< true if speed (implies direction) is controlled */
+ bool flag_control_position_enabled; /**< true if position is controlled */
+
+ bool flag_preflight_gyro_calibration; /**< true if gyro calibration is requested */
+ bool flag_preflight_mag_calibration; /**< true if mag calibration is requested */
+ bool flag_preflight_accel_calibration;
+ bool flag_preflight_airspeed_calibration;
+
+ bool rc_signal_found_once;
+ bool rc_signal_lost; /**< true if RC reception is terminally lost */
+ bool rc_signal_cutting_off; /**< true if RC reception is weak / cutting off */
+ uint64_t rc_signal_lost_interval; /**< interval in microseconds since when no RC signal is available */
+
+ bool offboard_control_signal_found_once;
+ bool offboard_control_signal_lost;
+ bool offboard_control_signal_weak;
+ uint64_t offboard_control_signal_lost_interval; /**< interval in microseconds without an offboard control message */
+
+ bool failsave_lowlevel; /**< Set to true if low-level failsafe mode is enabled */
+ //bool failsave_highlevel;
+
+ /* see SYS_STATUS mavlink message for the following */
+ uint32_t onboard_control_sensors_present;
+ uint32_t onboard_control_sensors_enabled;
+ uint32_t onboard_control_sensors_health;
+ float load;
+ float voltage_battery;
+ float current_battery;
+ float battery_remaining;
+ enum VEHICLE_BATTERY_WARNING battery_warning; /**< current battery warning mode, as defined by VEHICLE_BATTERY_WARNING enum */
+ uint16_t drop_rate_comm;
+ uint16_t errors_comm;
+ uint16_t errors_count1;
+ uint16_t errors_count2;
+ uint16_t errors_count3;
+ uint16_t errors_count4;
+
+ bool flag_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */
+ bool flag_local_position_valid;
+ bool flag_vector_flight_mode_ok; /**< position estimation, battery voltage and other critical subsystems are good for autonomous flight */
+ bool flag_auto_flight_mode_ok; /**< conditions of vector flight mode apply plus a valid takeoff position lock has been aquired */
+ bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
+ bool flag_valid_launch_position; /**< indicates a valid launch position */
+ bool flag_valid_home_position; /**< indicates a valid home position (a valid home position is not always a valid launch) */
+ bool flag_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_status);
+
+#endif
diff --git a/src/modules/uORB/topics/vehicle_vicon_position.h b/src/modules/uORB/topics/vehicle_vicon_position.h
new file mode 100644
index 000000000..0822fa89a
--- /dev/null
+++ b/src/modules/uORB/topics/vehicle_vicon_position.h
@@ -0,0 +1,78 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file vehicle_vicon_position.h
+ * Definition of the raw VICON Motion Capture position
+ */
+
+#ifndef TOPIC_VEHICLE_VICON_POSITION_H_
+#define TOPIC_VEHICLE_VICON_POSITION_H_
+
+#include <stdint.h>
+#include <stdbool.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Fused local position in NED.
+ */
+struct vehicle_vicon_position_s
+{
+ uint64_t timestamp; /**< time of this estimate, in microseconds since system start */
+ bool valid; /**< true if position satisfies validity criteria of estimator */
+
+ float x; /**< X positin in meters in NED earth-fixed frame */
+ float y; /**< X positin in meters in NED earth-fixed frame */
+ float z; /**< Z positin in meters in NED earth-fixed frame (negative altitude) */
+ float roll;
+ float pitch;
+ float yaw;
+
+ // TODO Add covariances here
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_vicon_position);
+
+#endif