aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB/topics
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
committerpx4dev <px4@purgatory.org>2012-08-04 15:12:36 -0700
commit8a365179eafdf3aea98e60ab9f5882b200d4c759 (patch)
tree4f38d6d4cd80bd0b6e22e2bb534c3f117ce44e56 /apps/uORB/topics
downloadpx4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.gz
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.tar.bz2
px4-firmware-8a365179eafdf3aea98e60ab9f5882b200d4c759.zip
Fresh import of the PX4 firmware sources.
Diffstat (limited to 'apps/uORB/topics')
-rw-r--r--apps/uORB/topics/UNPORTED_subsystem_info.h68
-rw-r--r--apps/uORB/topics/actuator_controls.h64
-rw-r--r--apps/uORB/topics/ardrone_control.h83
-rw-r--r--apps/uORB/topics/ardrone_motors_setpoint.h70
-rw-r--r--apps/uORB/topics/fixedwing_control.h77
-rw-r--r--apps/uORB/topics/rc_channels.h116
-rw-r--r--apps/uORB/topics/sensor_combined.h103
-rw-r--r--apps/uORB/topics/vehicle_attitude.h92
-rw-r--r--apps/uORB/topics/vehicle_attitude_setpoint.h77
-rw-r--r--apps/uORB/topics/vehicle_command.h79
-rw-r--r--apps/uORB/topics/vehicle_global_position.h86
-rw-r--r--apps/uORB/topics/vehicle_global_position_setpoint.h78
-rw-r--r--apps/uORB/topics/vehicle_gps_position.h89
-rw-r--r--apps/uORB/topics/vehicle_local_position.h87
-rw-r--r--apps/uORB/topics/vehicle_local_position_setpoint.h67
-rw-r--r--apps/uORB/topics/vehicle_status.h140
16 files changed, 1376 insertions, 0 deletions
diff --git a/apps/uORB/topics/UNPORTED_subsystem_info.h b/apps/uORB/topics/UNPORTED_subsystem_info.h
new file mode 100644
index 000000000..24f973a02
--- /dev/null
+++ b/apps/uORB/topics/UNPORTED_subsystem_info.h
@@ -0,0 +1,68 @@
+/* Structure for storage of shared variables (extended( */
+
+/* global_data_subsystem_info stores a buffer of the sensor info/status messages (sent by sensors or gps app), this is then handled by the commander. (The commander then writes to global_data_sys_status which is read by mavlink) */
+
+/* (any app) --> global_data_subsystem_info (buffered) --> (commander app) --> global_data_sys_status --> (mavlink app) */
+
+#ifndef GLOBAL_DATA_SUBSYSTEM_INFO_T_H_ //adjust this line!
+#define GLOBAL_DATA_SUBSYSTEM_INFO_T_H_ //adjust this line!
+
+#define SUBSYSTEM_INFO_BUFFER_SIZE 10
+
+#include "global_data_access.h"
+
+typedef enum //values correspond to bitmasks of mavlink message sys_status, this is crucial for the underlying bitmask to work
+{
+ SUBSYSTEM_TYPE_GYRO = 0,
+ SUBSYSTEM_TYPE_ACC = 1,
+ SUBSYSTEM_TYPE_MAG = 2,
+ SUBSYSTEM_TYPE_ABSPRESSURE = 3,
+ SUBSYSTEM_TYPE_DIFFPRESSURE = 4,
+ SUBSYSTEM_TYPE_GPS = 5,
+ SUBSYSTEM_TYPE_OPTICALFLOW = 6,
+ SUBSYSTEM_TYPE_CVPOSITION = 7,
+ SUBSYSTEM_TYPE_LASERPOSITION = 8,
+ SUBSYSTEM_TYPE_EXTERNALGROUNDTRUTH = 9,
+ SUBSYSTEM_TYPE_ANGULARRATECONTROL = 10,
+ SUBSYSTEM_TYPE_ATTITUDESTABILIZATION = 11,
+ SUBSYSTEM_TYPE_YAWPOSITION = 12,
+ SUBSYSTEM_TYPE_ALTITUDECONTROL = 13,
+ SUBSYSTEM_TYPE_POSITIONCONTROL = 14,
+ SUBSYSTEM_TYPE_MOTORCONTROL = 15
+
+} subsystem_type_t;
+
+typedef struct
+{
+ uint8_t present;
+ uint8_t enabled;
+ uint8_t health;
+
+ subsystem_type_t subsystem_type;
+
+} __attribute__((__packed__)) subsystem_info_t;
+
+typedef struct
+{
+ /* Struct which stores the access configuration, this is the same for all shared structs */
+
+ access_conf_t access_conf; //don't remove this line!
+
+ /* 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
+
+ /* Actual data, this is specific to the type of data which is stored in this struct */
+
+ //***** Start: Add your variables here *****
+ subsystem_info_t info[SUBSYSTEM_INFO_BUFFER_SIZE];
+ uint8_t current_info;
+
+ //*****END: Add your variables here *****
+
+} global_data_subsystem_info_t; //adjust this line!
+
+extern global_data_subsystem_info_t* global_data_subsystem_info; //adjust this line!
+
+#endif
diff --git a/apps/uORB/topics/actuator_controls.h b/apps/uORB/topics/actuator_controls.h
new file mode 100644
index 000000000..03c0c7b7d
--- /dev/null
+++ b/apps/uORB/topics/actuator_controls.h
@@ -0,0 +1,64 @@
+/****************************************************************************
+ *
+ * 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 control topic - mixer inputs.
+ *
+ * Values published to this topic 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.
+ */
+
+#ifndef TOPIC_ACTUATOR_CONTROLS_H
+#define TOPIC_ACTUATOR_CONTROLS_H
+
+#include <stdint.h>
+#include "../uORB.h"
+
+#define NUM_ACTUATOR_CONTROLS 16
+
+struct actuator_controls
+{
+ float control[NUM_ACTUATOR_CONTROLS];
+};
+
+ORB_DECLARE(actuator_controls);
+
+struct actuator_armed
+{
+ bool armed;
+};
+
+ORB_DECLARE(actuator_armed);
+
+#endif \ No newline at end of file
diff --git a/apps/uORB/topics/ardrone_control.h b/apps/uORB/topics/ardrone_control.h
new file mode 100644
index 000000000..1f582f52a
--- /dev/null
+++ b/apps/uORB/topics/ardrone_control.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * 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 ardrone_control.c
+ * Definition of the ardrone_control uORB topic.
+ */
+
+#ifndef TOPIC_ARDRONE_CONTROL_H_
+#define TOPIC_ARDRONE_CONTROL_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct ardrone_control_s
+{
+ uint16_t counter; /**< incremented by the publishing thread everytime new data is stored. */
+ uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data. */
+
+ float setpoint_rate_cast[3];
+ float setpoint_thrust_cast; /**< LOGME */
+ float setpoint_attitude_rate[3];
+ float setpoint_attitude[3]; /**< LOGME */
+ float attitude_control_output[3]; /**< roll, pitch, yaw. */
+ float position_control_output[3]; /**< x, y, z. */
+ float attitude_setpoint_navigationframe_from_positioncontroller[3]; /**< LOGME */
+ float gyro_scaled[3];
+ float gyro_filtered[3];
+ float gyro_filtered_offset[3];
+ float zcompensation;
+ uint16_t motor_front_nw;
+ uint16_t motor_right_ne;
+ uint16_t motor_back_se;
+ uint16_t motor_left_sw;
+
+}; /**< ardrone control status */
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(ardrone_control);
+
+#endif /* TOPIC_ARDRONE_CONTROL_H_ */
diff --git a/apps/uORB/topics/ardrone_motors_setpoint.h b/apps/uORB/topics/ardrone_motors_setpoint.h
new file mode 100644
index 000000000..54d81b706
--- /dev/null
+++ b/apps/uORB/topics/ardrone_motors_setpoint.h
@@ -0,0 +1,70 @@
+/****************************************************************************
+ *
+ * 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 ardrone_motors_setpoint.h
+ * Definition of the ardrone_motors_setpoint uORB topic.
+ */
+
+#ifndef TOPIC_ARDRONE_MOTORS_SETPOINT_H_
+#define TOPIC_ARDRONE_MOTORS_SETPOINT_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+struct ardrone_motors_setpoint_s
+{
+ 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
+
+ uint16_t motor_front_nw; ///< Front motor in + configuration, front left motor in x configuration
+ uint16_t motor_right_ne; ///< Right motor in + configuration, front right motor in x configuration
+ uint16_t motor_back_se; ///< Back motor in + configuration, back right motor in x configuration
+ uint16_t motor_left_sw; ///< Left motor in + configuration, back left motor in x configuration
+
+}; /**< AR.Drone low level motors */
+
+ /**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(ardrone_motors_setpoint);
+
+#endif
diff --git a/apps/uORB/topics/fixedwing_control.h b/apps/uORB/topics/fixedwing_control.h
new file mode 100644
index 000000000..e904709b6
--- /dev/null
+++ b/apps/uORB/topics/fixedwing_control.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 fixedwing_control.h
+ * Definition of the fixedwing_control uORB topic.
+ */
+
+#ifndef TOPIC_FIXEDWING_CONTROL_H_
+#define TOPIC_FIXEDWING_CONTROL_H_
+
+#include <stdint.h>
+#include "../uORB.h"
+
+/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * fixed wing control status.
+ */
+struct fixedwing_control_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
+
+ float setpoint_rate_cast[3];
+ float setpoint_attitude_rate[3];
+ float setpoint_attitude[3];
+ int16_t attitude_control_output[4]; /**< roll, pitch, yaw, throttle */
+ float position_control_output[4];
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(fixedwing_control);
+
+#endif //GLOBAL_DATA_FIXEDWING_CONTROL_T_H_
diff --git a/apps/uORB/topics/rc_channels.h b/apps/uORB/topics/rc_channels.h
new file mode 100644
index 000000000..5bd2adeec
--- /dev/null
+++ b/apps/uORB/topics/rc_channels.h
@@ -0,0 +1,116 @@
+/****************************************************************************
+ *
+ * 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
+ * @{
+ */
+
+enum RC_CHANNELS_STATUS
+{
+ UNKNOWN = 0,
+ KNOWN = 1,
+ SIGNAL = 2,
+ TIMEOUT = 3
+};
+
+/**
+ * This defines the mapping of the RC functions.
+ * The value assigned to the specific function corresponds to the entry of
+ * the channel array chan[].
+ * Ex. To read out the scaled Pitch value:
+ * pitch = global_data_rc_channels->chan[PITCH].scale;
+ * The override is on channel 8, since we don't usually have a 12 channel RC
+ * and channel 5/6 (GRAUPNER/FUTABA) are mapped to the second ROLL servo, which
+ * can only be disabled on more advanced RC sets.
+ */
+enum RC_CHANNELS_FUNCTION
+{
+ THROTTLE = 0,
+ ROLL = 1,
+ PITCH = 2,
+ YAW = 3,
+ OVERRIDE = 4,
+ FUNC_0 = 5,
+ FUNC_1 = 6,
+ FUNC_2 = 7,
+ FUNC_3 = 8,
+ FUNC_4 = 9,
+ FUNC_5 = 10,
+ FUNC_6 = 11,
+ RC_CHANNELS_FUNCTION_MAX = 12
+};
+
+struct rc_channels_s {
+
+ uint64_t timestamp; /**< In microseconds since boot time. */
+ uint64_t timestamp_last_valid; /**< timestamp of last valid RC signal. */
+ struct {
+ uint16_t mid; /**< midpoint (0). */
+ float scaling_factor; /**< scaling factor from raw counts to 0..1 */
+ uint16_t raw; /**< current raw value */
+ int16_t scale;
+ float scaled; /**< Scaled */
+ uint16_t override;
+ enum RC_CHANNELS_STATUS status; /**< status of the channel */
+ } chan[RC_CHANNELS_FUNCTION_MAX];
+ uint8_t chan_count; /**< maximum number of valid channels */
+
+ /*String array to store the names of the functions*/
+ const char function_name[RC_CHANNELS_FUNCTION_MAX][20];
+ uint8_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/apps/uORB/topics/sensor_combined.h b/apps/uORB/topics/sensor_combined.h
new file mode 100644
index 000000000..ecf5ea81d
--- /dev/null
+++ b/apps/uORB/topics/sensor_combined.h
@@ -0,0 +1,103 @@
+/****************************************************************************
+ *
+ * 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
+ * @{
+ */
+
+/**
+ * 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 LOGME */
+
+ int16_t gyro_raw[3]; /**< Raw sensor values of angular velocity LOGME */
+ uint16_t gyro_raw_counter; /**< Number of raw measurments taken LOGME */
+ float gyro_rad_s[3]; /**< Angular velocity in radian per seconds LOGME */
+ int16_t accelerometer_raw[3]; /**< Raw acceleration in NED body frame LOGME */
+ uint16_t accelerometer_raw_counter; /**< Number of raw acc measurements taken LOGME */
+ float accelerometer_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 LOGME */
+ int16_t magnetometer_raw[3]; /**< Raw magnetic field in NED body frame LOGME */
+ float magnetometer_ga[3]; /**< Magnetic field in NED body frame, in Gauss LOGME */
+ uint16_t magnetometer_raw_counter; /**< Number of raw mag measurements taken LOGME */
+ float baro_pres_mbar; /**< Barometric pressure, already temp. comp. LOGME */
+ float baro_alt_meter; /**< Altitude, already temp. comp. LOGME */
+ float baro_temp_celcius; /**< Temperature in degrees celsius LOGME */
+ float battery_voltage_v; /**< Battery voltage in volts, filtered LOGME */
+ float adc_voltage_v[3]; /**< ADC voltages of ADC Chan 11/12/13 or -1 LOGME */
+ uint16_t baro_raw_counter; /**< Number of raw baro measurements taken LOGME */
+ uint16_t battery_voltage_counter; /**< Number of voltage measurements taken LOGME */
+ bool battery_voltage_valid; /**< True if battery voltage can be measured LOGME */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(sensor_combined);
+
+#endif
diff --git a/apps/uORB/topics/vehicle_attitude.h b/apps/uORB/topics/vehicle_attitude.h
new file mode 100644
index 000000000..e365a6557
--- /dev/null
+++ b/apps/uORB/topics/vehicle_attitude.h
@@ -0,0 +1,92 @@
+/****************************************************************************
+ *
+ * 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 {
+
+ /*
+ * 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.
+ */
+ 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) LOGME */
+ float pitch; /**< Pitch angle (rad, Tait-Bryan, NED) LOGME */
+ float yaw; /**< Yaw angle (rad, Tait-Bryan, NED) LOGME */
+ float rollspeed; /**< Roll angular speed (rad/s, Tait-Bryan, NED) LOGME */
+ float pitchspeed; /**< Pitch angular speed (rad/s, Tait-Bryan, NED) LOGME */
+ float yawspeed; /**< Yaw angular speed (rad/s, Tait-Bryan, NED) LOGME */
+ 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 */
+ uint16_t counter; /**< Counter of all attitude messages (wraps) */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_attitude);
+
+#endif
diff --git a/apps/uORB/topics/vehicle_attitude_setpoint.h b/apps/uORB/topics/vehicle_attitude_setpoint.h
new file mode 100644
index 000000000..6b3757402
--- /dev/null
+++ b/apps/uORB/topics/vehicle_attitude_setpoint.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 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_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ float pitch_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ float yaw_tait_bryan; /**< Tait-Bryan angle in NED frame */
+ float tait_bryan_valid; /**< Set to true if Tait-Bryan 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/apps/uORB/topics/vehicle_command.h b/apps/uORB/topics/vehicle_command.h
new file mode 100644
index 000000000..dca928efd
--- /dev/null
+++ b/apps/uORB/topics/vehicle_command.h
@@ -0,0 +1,79 @@
+/****************************************************************************
+ *
+ * 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
+ * @{
+ */
+
+struct vehicle_command_s
+{
+ float param1; /**< Parameter 1, as defined by MAVLink MAV_CMD enum. */
+ float param2; /**< Parameter 2, as defined by MAVLink MAV_CMD enum. */
+ float param3; /**< Parameter 3, as defined by MAVLink MAV_CMD enum. */
+ float param4; /**< Parameter 4, as defined by MAVLink MAV_CMD enum. */
+ float param5; /**< Parameter 5, as defined by MAVLink MAV_CMD enum. */
+ float param6; /**< Parameter 6, as defined by MAVLink MAV_CMD enum. */
+ float param7; /**< Parameter 7, as defined by MAVLink MAV_CMD enum. */
+ uint16_t command; /**< Command ID, as defined MAVLink by MAV_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/apps/uORB/topics/vehicle_global_position.h b/apps/uORB/topics/vehicle_global_position.h
new file mode 100644
index 000000000..f036c7223
--- /dev/null
+++ b/apps/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/apps/uORB/topics/vehicle_global_position_setpoint.h b/apps/uORB/topics/vehicle_global_position_setpoint.h
new file mode 100644
index 000000000..b73e2a363
--- /dev/null
+++ b/apps/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/apps/uORB/topics/vehicle_gps_position.h b/apps/uORB/topics/vehicle_gps_position.h
new file mode 100644
index 000000000..60d01a831
--- /dev/null
+++ b/apps/uORB/topics/vehicle_gps_position.h
@@ -0,0 +1,89 @@
+/****************************************************************************
+ *
+ * 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; /**< Timestamp (microseconds since system boot) */
+ uint32_t counter; /**< Count of GPS messages */
+ uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */
+
+ int32_t lat; /**< Latitude in 1E7 degrees //LOGME */
+ int32_t lon; /**< Longitude in 1E7 degrees //LOGME */
+ int32_t alt; /**< Altitude in 1E3 meters (millimeters) above MSL //LOGME */
+ uint16_t counter_pos_valid; /**< is only increased when new lat/lon/alt information was added */
+ uint16_t eph; /**< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 //LOGME */
+ uint16_t epv; /**< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 */
+ uint16_t vel; /**< GPS ground speed (m/s * 100). If unknown, set to: 65535 */
+ uint16_t cog; /**< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 */
+ 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. */
+ 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 */
+ uint8_t 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/apps/uORB/topics/vehicle_local_position.h b/apps/uORB/topics/vehicle_local_position.h
new file mode 100644
index 000000000..76eddeacd
--- /dev/null
+++ b/apps/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/apps/uORB/topics/vehicle_local_position_setpoint.h b/apps/uORB/topics/vehicle_local_position_setpoint.h
new file mode 100644
index 000000000..d24d81e3a
--- /dev/null
+++ b/apps/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/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
new file mode 100644
index 000000000..d92b80046
--- /dev/null
+++ b/apps/uORB/topics/vehicle_status.h
@@ -0,0 +1,140 @@
+/****************************************************************************
+ *
+ * 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_STABILIZE_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 */
+
+/**
+ * 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 */
+
+ commander_state_machine_t state_machine;
+ uint8_t mode;
+
+ bool control_manual_enabled; /**< true if manual input is mixed in */
+ bool control_rates_enabled; /**< true if rates are stabilized */
+ bool control_attitude_enabled; /**< true if attitude stabilization is mixed in */
+ bool control_speed_enabled; /**< true if speed (implies direction) is controlled */
+ bool control_position_enabled; /**< true if position is controlled */
+
+ bool preflight_gyro_calibration; /**< true if gyro calibration is requested */
+ bool preflight_mag_calibration; /**< true if mag calibration is requested */
+
+ /* 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;
+ uint16_t load;
+ uint16_t voltage_battery;
+ int16_t current_battery;
+ int8_t battery_remaining;
+ 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 remote_manual; /**< set to true by the commander when the manual-switch on the remote is set to manual */
+ bool gps_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 */
+
+};
+
+/**
+ * @}
+ */
+
+/* register this as object request broker structure */
+ORB_DECLARE(vehicle_status);
+
+#endif