aboutsummaryrefslogtreecommitdiff
path: root/apps/uORB
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 /apps/uORB
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 'apps/uORB')
-rw-r--r--apps/uORB/.context0
-rw-r--r--apps/uORB/Makefile42
-rw-r--r--apps/uORB/objects_common.cpp153
-rw-r--r--apps/uORB/topics/actuator_controls.h77
-rw-r--r--apps/uORB/topics/actuator_controls_effective.h70
-rw-r--r--apps/uORB/topics/actuator_outputs.h70
-rw-r--r--apps/uORB/topics/battery_status.h68
-rw-r--r--apps/uORB/topics/debug_key_value.h75
-rw-r--r--apps/uORB/topics/differential_pressure.h71
-rw-r--r--apps/uORB/topics/home_position.h77
-rw-r--r--apps/uORB/topics/manual_control_setpoint.h88
-rw-r--r--apps/uORB/topics/offboard_control_setpoint.h94
-rw-r--r--apps/uORB/topics/omnidirectional_flow.h75
-rw-r--r--apps/uORB/topics/optical_flow.h77
-rw-r--r--apps/uORB/topics/parameter_update.h52
-rw-r--r--apps/uORB/topics/rc_channels.h108
-rw-r--r--apps/uORB/topics/sensor_combined.h115
-rw-r--r--apps/uORB/topics/subsystem_info.h97
-rwxr-xr-xapps/uORB/topics/vehicle_attitude.h90
-rw-r--r--apps/uORB/topics/vehicle_attitude_setpoint.h78
-rw-r--r--apps/uORB/topics/vehicle_command.h140
-rw-r--r--apps/uORB/topics/vehicle_global_position.h86
-rw-r--r--apps/uORB/topics/vehicle_global_position_set_triplet.h78
-rw-r--r--apps/uORB/topics/vehicle_global_position_setpoint.h78
-rw-r--r--apps/uORB/topics/vehicle_gps_position.h100
-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_rates_setpoint.h68
-rw-r--r--apps/uORB/topics/vehicle_status.h226
-rw-r--r--apps/uORB/topics/vehicle_vicon_position.h78
-rw-r--r--apps/uORB/uORB.cpp1006
-rw-r--r--apps/uORB/uORB.h264
32 files changed, 0 insertions, 3855 deletions
diff --git a/apps/uORB/.context b/apps/uORB/.context
deleted file mode 100644
index e69de29bb..000000000
--- a/apps/uORB/.context
+++ /dev/null
diff --git a/apps/uORB/Makefile b/apps/uORB/Makefile
deleted file mode 100644
index 64ba52e9c..000000000
--- a/apps/uORB/Makefile
+++ /dev/null
@@ -1,42 +0,0 @@
-############################################################################
-#
-# 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.
-#
-############################################################################
-
-#
-# Makefile to build uORB
-#
-
-APPNAME = uorb
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 4096
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/uORB/objects_common.cpp b/apps/uORB/objects_common.cpp
deleted file mode 100644
index 136375140..000000000
--- a/apps/uORB/objects_common.cpp
+++ /dev/null
@@ -1,153 +0,0 @@
-/****************************************************************************
- *
- * 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 objects_common.cpp
- *
- * Common object definitions without a better home.
- */
-
-#include <nuttx/config.h>
-
-#include <drivers/drv_orb_dev.h>
-
-#include <drivers/drv_mag.h>
-ORB_DEFINE(sensor_mag, struct mag_report);
-
-#include <drivers/drv_accel.h>
-ORB_DEFINE(sensor_accel, struct accel_report);
-
-#include <drivers/drv_gyro.h>
-ORB_DEFINE(sensor_gyro, struct gyro_report);
-
-#include <drivers/drv_baro.h>
-ORB_DEFINE(sensor_baro, struct baro_report);
-
-#include <drivers/drv_range_finder.h>
-ORB_DEFINE(sensor_range_finder, struct range_finder_report);
-
-#include <drivers/drv_pwm_output.h>
-ORB_DEFINE(output_pwm, struct pwm_output_values);
-
-#include <drivers/drv_rc_input.h>
-ORB_DEFINE(input_rc, struct rc_input_values);
-
-#include "topics/vehicle_attitude.h"
-ORB_DEFINE(vehicle_attitude, struct vehicle_attitude_s);
-
-#include "topics/sensor_combined.h"
-ORB_DEFINE(sensor_combined, struct sensor_combined_s);
-
-#include "topics/vehicle_gps_position.h"
-ORB_DEFINE(vehicle_gps_position, struct vehicle_gps_position_s);
-
-#include "topics/home_position.h"
-ORB_DEFINE(home_position, struct home_position_s);
-
-#include "topics/vehicle_status.h"
-ORB_DEFINE(vehicle_status, struct vehicle_status_s);
-
-#include "topics/battery_status.h"
-ORB_DEFINE(battery_status, struct battery_status_s);
-
-#include "topics/vehicle_global_position.h"
-ORB_DEFINE(vehicle_global_position, struct vehicle_global_position_s);
-
-#include "topics/vehicle_local_position.h"
-ORB_DEFINE(vehicle_local_position, struct vehicle_local_position_s);
-
-#include "topics/vehicle_vicon_position.h"
-ORB_DEFINE(vehicle_vicon_position, struct vehicle_vicon_position_s);
-
-#include "topics/vehicle_rates_setpoint.h"
-ORB_DEFINE(vehicle_rates_setpoint, struct vehicle_rates_setpoint_s);
-
-#include "topics/rc_channels.h"
-ORB_DEFINE(rc_channels, struct rc_channels_s);
-
-#include "topics/vehicle_command.h"
-ORB_DEFINE(vehicle_command, struct vehicle_command_s);
-
-#include "topics/vehicle_local_position_setpoint.h"
-ORB_DEFINE(vehicle_local_position_setpoint, struct vehicle_local_position_setpoint_s);
-
-#include "topics/vehicle_global_position_setpoint.h"
-ORB_DEFINE(vehicle_global_position_setpoint, struct vehicle_global_position_setpoint_s);
-
-#include "topics/vehicle_global_position_set_triplet.h"
-ORB_DEFINE(vehicle_global_position_set_triplet, struct vehicle_global_position_set_triplet_s);
-
-#include "topics/vehicle_attitude_setpoint.h"
-ORB_DEFINE(vehicle_attitude_setpoint, struct vehicle_attitude_setpoint_s);
-
-#include "topics/manual_control_setpoint.h"
-ORB_DEFINE(manual_control_setpoint, struct manual_control_setpoint_s);
-
-#include "topics/offboard_control_setpoint.h"
-ORB_DEFINE(offboard_control_setpoint, struct offboard_control_setpoint_s);
-
-#include "topics/optical_flow.h"
-ORB_DEFINE(optical_flow, struct optical_flow_s);
-
-#include "topics/omnidirectional_flow.h"
-ORB_DEFINE(omnidirectional_flow, struct omnidirectional_flow_s);
-
-#include "topics/differential_pressure.h"
-ORB_DEFINE(differential_pressure, struct differential_pressure_s);
-
-#include "topics/subsystem_info.h"
-ORB_DEFINE(subsystem_info, struct subsystem_info_s);
-
-/* actuator controls, as requested by controller */
-#include "topics/actuator_controls.h"
-ORB_DEFINE(actuator_controls_0, struct actuator_controls_s);
-ORB_DEFINE(actuator_controls_1, struct actuator_controls_s);
-ORB_DEFINE(actuator_controls_2, struct actuator_controls_s);
-ORB_DEFINE(actuator_controls_3, struct actuator_controls_s);
-ORB_DEFINE(actuator_armed, struct actuator_armed_s);
-
-/* actuator controls, as set by actuators / mixers after limiting */
-#include "topics/actuator_controls_effective.h"
-ORB_DEFINE(actuator_controls_effective_0, struct actuator_controls_effective_s);
-ORB_DEFINE(actuator_controls_effective_1, struct actuator_controls_effective_s);
-ORB_DEFINE(actuator_controls_effective_2, struct actuator_controls_effective_s);
-ORB_DEFINE(actuator_controls_effective_3, struct actuator_controls_effective_s);
-
-#include "topics/actuator_outputs.h"
-ORB_DEFINE(actuator_outputs_0, struct actuator_outputs_s);
-ORB_DEFINE(actuator_outputs_1, struct actuator_outputs_s);
-ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s);
-ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s);
-
-#include "topics/debug_key_value.h"
-ORB_DEFINE(debug_key_value, struct debug_key_value_s);
diff --git a/apps/uORB/topics/actuator_controls.h b/apps/uORB/topics/actuator_controls.h
deleted file mode 100644
index 0b50a29ac..000000000
--- a/apps/uORB/topics/actuator_controls.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/actuator_controls_effective.h b/apps/uORB/topics/actuator_controls_effective.h
deleted file mode 100644
index 088c4fc8f..000000000
--- a/apps/uORB/topics/actuator_controls_effective.h
+++ /dev/null
@@ -1,70 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/actuator_outputs.h b/apps/uORB/topics/actuator_outputs.h
deleted file mode 100644
index bbe429073..000000000
--- a/apps/uORB/topics/actuator_outputs.h
+++ /dev/null
@@ -1,70 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/battery_status.h b/apps/uORB/topics/battery_status.h
deleted file mode 100644
index c40d0d4e5..000000000
--- a/apps/uORB/topics/battery_status.h
+++ /dev/null
@@ -1,68 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/debug_key_value.h b/apps/uORB/topics/debug_key_value.h
deleted file mode 100644
index a9d1b83fd..000000000
--- a/apps/uORB/topics/debug_key_value.h
+++ /dev/null
@@ -1,75 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/differential_pressure.h b/apps/uORB/topics/differential_pressure.h
deleted file mode 100644
index d5e4bf37e..000000000
--- a/apps/uORB/topics/differential_pressure.h
+++ /dev/null
@@ -1,71 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/home_position.h b/apps/uORB/topics/home_position.h
deleted file mode 100644
index 7e1b82a0f..000000000
--- a/apps/uORB/topics/home_position.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/manual_control_setpoint.h b/apps/uORB/topics/manual_control_setpoint.h
deleted file mode 100644
index 261a8a4ad..000000000
--- a/apps/uORB/topics/manual_control_setpoint.h
+++ /dev/null
@@ -1,88 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/offboard_control_setpoint.h b/apps/uORB/topics/offboard_control_setpoint.h
deleted file mode 100644
index 2e895c59c..000000000
--- a/apps/uORB/topics/offboard_control_setpoint.h
+++ /dev/null
@@ -1,94 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/omnidirectional_flow.h b/apps/uORB/topics/omnidirectional_flow.h
deleted file mode 100644
index 8f4be3b3f..000000000
--- a/apps/uORB/topics/omnidirectional_flow.h
+++ /dev/null
@@ -1,75 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/optical_flow.h b/apps/uORB/topics/optical_flow.h
deleted file mode 100644
index c854f0079..000000000
--- a/apps/uORB/topics/optical_flow.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/parameter_update.h b/apps/uORB/topics/parameter_update.h
deleted file mode 100644
index 300e895c7..000000000
--- a/apps/uORB/topics/parameter_update.h
+++ /dev/null
@@ -1,52 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/rc_channels.h b/apps/uORB/topics/rc_channels.h
deleted file mode 100644
index 9dd54df91..000000000
--- a/apps/uORB/topics/rc_channels.h
+++ /dev/null
@@ -1,108 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/sensor_combined.h b/apps/uORB/topics/sensor_combined.h
deleted file mode 100644
index 961ee8b4a..000000000
--- a/apps/uORB/topics/sensor_combined.h
+++ /dev/null
@@ -1,115 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/subsystem_info.h b/apps/uORB/topics/subsystem_info.h
deleted file mode 100644
index c415e832e..000000000
--- a/apps/uORB/topics/subsystem_info.h
+++ /dev/null
@@ -1,97 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_attitude.h b/apps/uORB/topics/vehicle_attitude.h
deleted file mode 100755
index c31c81d0c..000000000
--- a/apps/uORB/topics/vehicle_attitude.h
+++ /dev/null
@@ -1,90 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_attitude_setpoint.h b/apps/uORB/topics/vehicle_attitude_setpoint.h
deleted file mode 100644
index a7cda34a8..000000000
--- a/apps/uORB/topics/vehicle_attitude_setpoint.h
+++ /dev/null
@@ -1,78 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_command.h b/apps/uORB/topics/vehicle_command.h
deleted file mode 100644
index fac571659..000000000
--- a/apps/uORB/topics/vehicle_command.h
+++ /dev/null
@@ -1,140 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_global_position.h b/apps/uORB/topics/vehicle_global_position.h
deleted file mode 100644
index f036c7223..000000000
--- a/apps/uORB/topics/vehicle_global_position.h
+++ /dev/null
@@ -1,86 +0,0 @@
-/****************************************************************************
- *
- * 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_set_triplet.h b/apps/uORB/topics/vehicle_global_position_set_triplet.h
deleted file mode 100644
index 318abba89..000000000
--- a/apps/uORB/topics/vehicle_global_position_set_triplet.h
+++ /dev/null
@@ -1,78 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_global_position_setpoint.h b/apps/uORB/topics/vehicle_global_position_setpoint.h
deleted file mode 100644
index eec6a8229..000000000
--- a/apps/uORB/topics/vehicle_global_position_setpoint.h
+++ /dev/null
@@ -1,78 +0,0 @@
-/****************************************************************************
- *
- * 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
deleted file mode 100644
index 0a7fb4e9d..000000000
--- a/apps/uORB/topics/vehicle_gps_position.h
+++ /dev/null
@@ -1,100 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_local_position.h b/apps/uORB/topics/vehicle_local_position.h
deleted file mode 100644
index 76eddeacd..000000000
--- a/apps/uORB/topics/vehicle_local_position.h
+++ /dev/null
@@ -1,87 +0,0 @@
-/****************************************************************************
- *
- * 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
deleted file mode 100644
index d24d81e3a..000000000
--- a/apps/uORB/topics/vehicle_local_position_setpoint.h
+++ /dev/null
@@ -1,67 +0,0 @@
-/****************************************************************************
- *
- * 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_rates_setpoint.h b/apps/uORB/topics/vehicle_rates_setpoint.h
deleted file mode 100644
index 46e62c4b7..000000000
--- a/apps/uORB/topics/vehicle_rates_setpoint.h
+++ /dev/null
@@ -1,68 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_status.h b/apps/uORB/topics/vehicle_status.h
deleted file mode 100644
index c7c1048f6..000000000
--- a/apps/uORB/topics/vehicle_status.h
+++ /dev/null
@@ -1,226 +0,0 @@
-/****************************************************************************
- *
- * 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/apps/uORB/topics/vehicle_vicon_position.h b/apps/uORB/topics/vehicle_vicon_position.h
deleted file mode 100644
index 0822fa89a..000000000
--- a/apps/uORB/topics/vehicle_vicon_position.h
+++ /dev/null
@@ -1,78 +0,0 @@
-/****************************************************************************
- *
- * 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
diff --git a/apps/uORB/uORB.cpp b/apps/uORB/uORB.cpp
deleted file mode 100644
index 7abbf42ae..000000000
--- a/apps/uORB/uORB.cpp
+++ /dev/null
@@ -1,1006 +0,0 @@
-/****************************************************************************
- *
- * 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 uORB.cpp
- * A lightweight object broker.
- */
-
-#include <nuttx/config.h>
-
-#include <drivers/device/device.h>
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-#include <string.h>
-#include <stdlib.h>
-#include <fcntl.h>
-#include <poll.h>
-#include <errno.h>
-#include <stdio.h>
-#include <math.h>
-#include <unistd.h>
-
-#include <nuttx/arch.h>
-#include <nuttx/wqueue.h>
-#include <nuttx/clock.h>
-
-#include <drivers/drv_hrt.h>
-
-#include <drivers/drv_orb_dev.h>
-
-#include "uORB.h"
-
-/**
- * Utility functions.
- */
-namespace
-{
-
-static const unsigned orb_maxpath = 64;
-
-/* oddly, ERROR is not defined for c++ */
-#ifdef ERROR
-# undef ERROR
-#endif
-const int ERROR = -1;
-
-enum Flavor {
- PUBSUB,
- PARAM
-};
-
-int
-node_mkpath(char *buf, Flavor f, const struct orb_metadata *meta)
-{
- unsigned len;
-
- len = snprintf(buf, orb_maxpath, "/%s/%s",
- (f == PUBSUB) ? "obj" : "param",
- meta->o_name);
-
- if (len >= orb_maxpath)
- return -ENAMETOOLONG;
-
- return OK;
-}
-
-}
-
-/**
- * Per-object device instance.
- */
-class ORBDevNode : public device::CDev
-{
-public:
- ORBDevNode(const struct orb_metadata *meta, const char *name, const char *path);
- ~ORBDevNode();
-
- virtual int open(struct file *filp);
- virtual int close(struct file *filp);
- virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
- virtual ssize_t write(struct file *filp, const char *buffer, size_t buflen);
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-
- static ssize_t publish(const orb_metadata *meta, orb_advert_t handle, const void *data);
-
-protected:
- virtual pollevent_t poll_state(struct file *filp);
- virtual void poll_notify_one(struct pollfd *fds, pollevent_t events);
-
-private:
- struct SubscriberData {
- unsigned generation; /**< last generation the subscriber has seen */
- unsigned update_interval; /**< if nonzero minimum interval between updates */
- struct hrt_call update_call; /**< deferred wakeup call if update_period is nonzero */
- void *poll_priv; /**< saved copy of fds->f_priv while poll is active */
- bool update_reported; /**< true if we have reported the update via poll/check */
- };
-
- const struct orb_metadata *_meta; /**< object metadata information */
- uint8_t *_data; /**< allocated object buffer */
- hrt_abstime _last_update; /**< time the object was last updated */
- volatile unsigned _generation; /**< object generation count */
- pid_t _publisher; /**< if nonzero, current publisher */
-
- SubscriberData *filp_to_sd(struct file *filp) {
- SubscriberData *sd = (SubscriberData *)(filp->f_priv);
- return sd;
- }
-
- /**
- * Perform a deferred update for a rate-limited subscriber.
- */
- void update_deferred();
-
- /**
- * Bridge from hrt_call to update_deferred
- *
- * void *arg ORBDevNode pointer for which the deferred update is performed.
- */
- static void update_deferred_trampoline(void *arg);
-
- /**
- * Check whether a topic appears updated to a subscriber.
- *
- * @param sd The subscriber for whom to check.
- * @return True if the topic should appear updated to the subscriber
- */
- bool appears_updated(SubscriberData *sd);
-};
-
-ORBDevNode::ORBDevNode(const struct orb_metadata *meta, const char *name, const char *path) :
- CDev(name, path),
- _meta(meta),
- _data(nullptr),
- _last_update(0),
- _generation(0),
- _publisher(0)
-{
- // enable debug() calls
- _debug_enabled = true;
-}
-
-ORBDevNode::~ORBDevNode()
-{
- if (_data != nullptr)
- delete[] _data;
-}
-
-int
-ORBDevNode::open(struct file *filp)
-{
- int ret;
-
- /* is this a publisher? */
- if (filp->f_oflags == O_WRONLY) {
-
- /* become the publisher if we can */
- lock();
-
- if (_publisher == 0) {
- _publisher = getpid();
- ret = OK;
-
- } else {
- ret = -EBUSY;
- }
-
- unlock();
-
- /* now complete the open */
- if (ret == OK) {
- ret = CDev::open(filp);
-
- /* open failed - not the publisher anymore */
- if (ret != OK)
- _publisher = 0;
- }
-
- return ret;
- }
-
- /* is this a new subscriber? */
- if (filp->f_oflags == O_RDONLY) {
-
- /* allocate subscriber data */
- SubscriberData *sd = new SubscriberData;
-
- if (nullptr == sd)
- return -ENOMEM;
-
- memset(sd, 0, sizeof(*sd));
-
- /* default to no pending update */
- sd->generation = _generation;
-
- filp->f_priv = (void *)sd;
-
- ret = CDev::open(filp);
-
- if (ret != OK)
- free(sd);
-
- return ret;
- }
-
- /* can only be pub or sub, not both */
- return -EINVAL;
-}
-
-int
-ORBDevNode::close(struct file *filp)
-{
- /* is this the publisher closing? */
- if (getpid() == _publisher) {
- _publisher = 0;
-
- } else {
- SubscriberData *sd = filp_to_sd(filp);
-
- if (sd != nullptr)
- delete sd;
- }
-
- return CDev::close(filp);
-}
-
-ssize_t
-ORBDevNode::read(struct file *filp, char *buffer, size_t buflen)
-{
- SubscriberData *sd = (SubscriberData *)filp_to_sd(filp);
-
- /* if the object has not been written yet, return zero */
- if (_data == nullptr)
- return 0;
-
- /* if the caller's buffer is the wrong size, that's an error */
- if (buflen != _meta->o_size)
- return -EIO;
-
- /*
- * Perform an atomic copy & state update
- */
- irqstate_t flags = irqsave();
-
- /* if the caller doesn't want the data, don't give it to them */
- if (nullptr != buffer)
- memcpy(buffer, _data, _meta->o_size);
-
- /* track the last generation that the file has seen */
- sd->generation = _generation;
-
- /*
- * Clear the flag that indicates that an update has been reported, as
- * we have just collected it.
- */
- sd->update_reported = false;
-
- irqrestore(flags);
-
- return _meta->o_size;
-}
-
-ssize_t
-ORBDevNode::write(struct file *filp, const char *buffer, size_t buflen)
-{
- /*
- * Writes are legal from interrupt context as long as the
- * object has already been initialised from thread context.
- *
- * Writes outside interrupt context will allocate the object
- * if it has not yet been allocated.
- *
- * Note that filp will usually be NULL.
- */
- if (nullptr == _data) {
- if (!up_interrupt_context()) {
-
- lock();
-
- /* re-check size */
- if (nullptr == _data)
- _data = new uint8_t[_meta->o_size];
-
- unlock();
- }
-
- /* failed or could not allocate */
- if (nullptr == _data)
- return -ENOMEM;
- }
-
- /* If write size does not match, that is an error */
- if (_meta->o_size != buflen)
- return -EIO;
-
- /* Perform an atomic copy. */
- irqstate_t flags = irqsave();
- memcpy(_data, buffer, _meta->o_size);
- irqrestore(flags);
-
- /* update the timestamp and generation count */
- _last_update = hrt_absolute_time();
- _generation++;
-
- /* notify any poll waiters */
- poll_notify(POLLIN);
-
- return _meta->o_size;
-}
-
-int
-ORBDevNode::ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- SubscriberData *sd = filp_to_sd(filp);
-
- switch (cmd) {
- case ORBIOCLASTUPDATE:
- *(hrt_abstime *)arg = _last_update;
- return OK;
-
- case ORBIOCUPDATED:
- *(bool *)arg = appears_updated(sd);
- return OK;
-
- case ORBIOCSETINTERVAL:
- sd->update_interval = arg;
- return OK;
-
- case ORBIOCGADVERTISER:
- *(uintptr_t *)arg = (uintptr_t)this;
- return OK;
-
- default:
- /* give it to the superclass */
- return CDev::ioctl(filp, cmd, arg);
- }
-}
-
-ssize_t
-ORBDevNode::publish(const orb_metadata *meta, orb_advert_t handle, const void *data)
-{
- ORBDevNode *devnode = (ORBDevNode *)handle;
- int ret;
-
- /* this is a bit risky, since we are trusting the handle in order to deref it */
- if (devnode->_meta != meta) {
- errno = EINVAL;
- return ERROR;
- }
-
- /* call the devnode write method with no file pointer */
- ret = devnode->write(nullptr, (const char *)data, meta->o_size);
-
- if (ret < 0)
- return ERROR;
-
- if (ret != (int)meta->o_size) {
- errno = EIO;
- return ERROR;
- }
-
- return OK;
-}
-
-pollevent_t
-ORBDevNode::poll_state(struct file *filp)
-{
- SubscriberData *sd = filp_to_sd(filp);
-
- /*
- * If the topic appears updated to the subscriber, say so.
- */
- if (appears_updated(sd))
- return POLLIN;
-
- return 0;
-}
-
-void
-ORBDevNode::poll_notify_one(struct pollfd *fds, pollevent_t events)
-{
- SubscriberData *sd = filp_to_sd((struct file *)fds->priv);
-
- /*
- * If the topic looks updated to the subscriber, go ahead and notify them.
- */
- if (appears_updated(sd))
- CDev::poll_notify_one(fds, events);
-}
-
-bool
-ORBDevNode::appears_updated(SubscriberData *sd)
-{
- /* assume it doesn't look updated */
- bool ret = false;
-
- /* avoid racing between interrupt and non-interrupt context calls */
- irqstate_t state = irqsave();
-
- /* check if this topic has been published yet, if not bail out */
- if (_data == nullptr) {
- ret = false;
- goto out;
- }
-
- /*
- * If the subscriber's generation count matches the update generation
- * count, there has been no update from their perspective; if they
- * don't match then we might have a visible update.
- */
- while (sd->generation != _generation) {
-
- /*
- * Handle non-rate-limited subscribers.
- */
- if (sd->update_interval == 0) {
- ret = true;
- break;
- }
-
- /*
- * If we have previously told the subscriber that there is data,
- * and they have not yet collected it, continue to tell them
- * that there has been an update. This mimics the non-rate-limited
- * behaviour where checking / polling continues to report an update
- * until the topic is read.
- */
- if (sd->update_reported) {
- ret = true;
- break;
- }
-
- /*
- * If the interval timer is still running, the topic should not
- * appear updated, even though at this point we know that it has.
- * We have previously been through here, so the subscriber
- * must have collected the update we reported, otherwise
- * update_reported would still be true.
- */
- if (!hrt_called(&sd->update_call))
- break;
-
- /*
- * Make sure that we don't consider the topic to be updated again
- * until the interval has passed once more by restarting the interval
- * timer and thereby re-scheduling a poll notification at that time.
- */
- hrt_call_after(&sd->update_call,
- sd->update_interval,
- &ORBDevNode::update_deferred_trampoline,
- (void *)this);
-
- /*
- * Remember that we have told the subscriber that there is data.
- */
- sd->update_reported = true;
- ret = true;
-
- break;
- }
-
-out:
- irqrestore(state);
-
- /* consider it updated */
- return ret;
-}
-
-void
-ORBDevNode::update_deferred()
-{
- /*
- * Instigate a poll notification; any subscribers whose intervals have
- * expired will be woken.
- */
- poll_notify(POLLIN);
-}
-
-void
-ORBDevNode::update_deferred_trampoline(void *arg)
-{
- ORBDevNode *node = (ORBDevNode *)arg;
-
- node->update_deferred();
-}
-
-/**
- * Master control device for ObjDev.
- *
- * Used primarily to create new objects via the ORBIOCCREATE
- * ioctl.
- */
-class ORBDevMaster : public device::CDev
-{
-public:
- ORBDevMaster(Flavor f);
- ~ORBDevMaster();
-
- virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
-private:
- Flavor _flavor;
-};
-
-ORBDevMaster::ORBDevMaster(Flavor f) :
- CDev((f == PUBSUB) ? "obj_master" : "param_master",
- (f == PUBSUB) ? TOPIC_MASTER_DEVICE_PATH : PARAM_MASTER_DEVICE_PATH),
- _flavor(f)
-{
- // enable debug() calls
- _debug_enabled = true;
-
-}
-
-ORBDevMaster::~ORBDevMaster()
-{
-}
-
-int
-ORBDevMaster::ioctl(struct file *filp, int cmd, unsigned long arg)
-{
- int ret;
-
- switch (cmd) {
- case ORBIOCADVERTISE: {
- const struct orb_metadata *meta = (const struct orb_metadata *)arg;
- const char *objname;
- char nodepath[orb_maxpath];
- ORBDevNode *node;
-
- /* construct a path to the node - this also checks the node name */
- ret = node_mkpath(nodepath, _flavor, meta);
-
- if (ret != OK)
- return ret;
-
- /* driver wants a permanent copy of the node name, so make one here */
- objname = strdup(meta->o_name);
-
- if (objname == nullptr)
- return -ENOMEM;
-
- /* construct the new node */
- node = new ORBDevNode(meta, objname, nodepath);
-
- /* initialise the node - this may fail if e.g. a node with this name already exists */
- if (node != nullptr)
- ret = node->init();
-
- /* if we didn't get a device, that's bad */
- if (node == nullptr)
- return -ENOMEM;
-
- /* if init failed, discard the node and its name */
- if (ret != OK) {
- delete node;
- free((void *)objname);
- }
-
- return ret;
- }
-
- default:
- /* give it to the superclass */
- return CDev::ioctl(filp, cmd, arg);
- }
-}
-
-
-/**
- * Local functions in support of the shell command.
- */
-
-namespace
-{
-
-ORBDevMaster *g_dev;
-
-struct orb_test {
- int val;
-};
-
-ORB_DEFINE(orb_test, struct orb_test);
-
-int
-test_fail(const char *fmt, ...)
-{
- va_list ap;
-
- fprintf(stderr, "FAIL: ");
- va_start(ap, fmt);
- vfprintf(stderr, fmt, ap);
- va_end(ap);
- fprintf(stderr, "\n");
- fflush(stderr);
- return ERROR;
-}
-
-int
-test_note(const char *fmt, ...)
-{
- va_list ap;
-
- fprintf(stderr, "note: ");
- va_start(ap, fmt);
- vfprintf(stderr, fmt, ap);
- va_end(ap);
- fprintf(stderr, "\n");
- fflush(stderr);
- return OK;
-}
-
-ORB_DECLARE(sensor_combined);
-
-int
-test()
-{
- struct orb_test t, u;
- int pfd, sfd;
- bool updated;
-
- t.val = 0;
- pfd = orb_advertise(ORB_ID(orb_test), &t);
-
- if (pfd < 0)
- return test_fail("advertise failed: %d", errno);
-
- test_note("publish handle 0x%08x", pfd);
- sfd = orb_subscribe(ORB_ID(orb_test));
-
- if (sfd < 0)
- return test_fail("subscribe failed: %d", errno);
-
- test_note("subscribe fd %d", sfd);
- u.val = 1;
-
- if (OK != orb_copy(ORB_ID(orb_test), sfd, &u))
- return test_fail("copy(1) failed: %d", errno);
-
- if (u.val != t.val)
- return test_fail("copy(1) mismatch: %d expected %d", u.val, t.val);
-
- if (OK != orb_check(sfd, &updated))
- return test_fail("check(1) failed");
-
- if (updated)
- return test_fail("spurious updated flag");
-
- t.val = 2;
- test_note("try publish");
-
- if (OK != orb_publish(ORB_ID(orb_test), pfd, &t))
- return test_fail("publish failed");
-
- if (OK != orb_check(sfd, &updated))
- return test_fail("check(2) failed");
-
- if (!updated)
- return test_fail("missing updated flag");
-
- if (OK != orb_copy(ORB_ID(orb_test), sfd, &u))
- return test_fail("copy(2) failed: %d", errno);
-
- if (u.val != t.val)
- return test_fail("copy(2) mismatch: %d expected %d", u.val, t.val);
-
- orb_unsubscribe(sfd);
- close(pfd);
-
-#if 0
- /* this is a hacky test that exploits the sensors app to test rate-limiting */
-
- sfd = orb_subscribe(ORB_ID(sensor_combined));
-
- hrt_abstime start, end;
- unsigned count;
-
- start = hrt_absolute_time();
- count = 0;
-
- do {
- orb_check(sfd, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(sensor_combined), sfd, nullptr);
- count++;
- }
- } while (count < 100);
-
- end = hrt_absolute_time();
- test_note("full-speed, 100 updates in %llu", end - start);
-
- orb_set_interval(sfd, 10);
-
- start = hrt_absolute_time();
- count = 0;
-
- do {
- orb_check(sfd, &updated);
-
- if (updated) {
- orb_copy(ORB_ID(sensor_combined), sfd, nullptr);
- count++;
- }
- } while (count < 100);
-
- end = hrt_absolute_time();
- test_note("100Hz, 100 updates in %llu", end - start);
-
- orb_unsubscribe(sfd);
-#endif
-
- return test_note("PASS");
-}
-
-int
-info()
-{
- return OK;
-}
-
-
-} // namespace
-
-/*
- * uORB server 'main'.
- */
-extern "C" { __EXPORT int uorb_main(int argc, char *argv[]); }
-
-int
-uorb_main(int argc, char *argv[])
-{
- /*
- * Start/load the driver.
- *
- * XXX it would be nice to have a wrapper for this...
- */
- if (!strcmp(argv[1], "start")) {
-
- if (g_dev != nullptr) {
- fprintf(stderr, "[uorb] already loaded\n");
- /* user wanted to start uorb, its already running, no error */
- return 0;
- }
-
- /* create the driver */
- g_dev = new ORBDevMaster(PUBSUB);
-
- if (g_dev == nullptr) {
- fprintf(stderr, "[uorb] driver alloc failed\n");
- return -ENOMEM;
- }
-
- if (OK != g_dev->init()) {
- fprintf(stderr, "[uorb] driver init failed\n");
- delete g_dev;
- g_dev = nullptr;
- return -EIO;
- }
-
- printf("[uorb] ready\n");
- return OK;
- }
-
- /*
- * Test the driver/device.
- */
- if (!strcmp(argv[1], "test"))
- return test();
-
- /*
- * Print driver information.
- */
- if (!strcmp(argv[1], "status"))
- return info();
-
- fprintf(stderr, "unrecognised command, try 'start', 'test' or 'status'\n");
- return -EINVAL;
-}
-
-/*
- * Library functions.
- */
-namespace
-{
-
-void debug(const char *fmt, ...)
-{
- va_list ap;
-
- va_start(ap, fmt);
- vfprintf(stderr, fmt, ap);
- va_end(ap);
- fprintf(stderr, "\n");
- fflush(stderr);
- usleep(100000);
-}
-
-/**
- * Advertise a node; don't consider it an error if the node has
- * already been advertised.
- *
- * @todo verify that the existing node is the same as the one
- * we tried to advertise.
- */
-int
-node_advertise(const struct orb_metadata *meta)
-{
- int fd = -1;
- int ret = ERROR;
-
- /* open the control device */
- fd = open(TOPIC_MASTER_DEVICE_PATH, 0);
-
- if (fd < 0)
- goto out;
-
- /* advertise the object */
- ret = ioctl(fd, ORBIOCADVERTISE, (unsigned long)(uintptr_t)meta);
-
- /* it's OK if it already exists */
- if ((OK != ret) && (EEXIST == errno))
- ret = OK;
-
-out:
-
- if (fd >= 0)
- close(fd);
-
- return ret;
-}
-
-/**
- * Common implementation for orb_advertise and orb_subscribe.
- *
- * Handles creation of the object and the initial publication for
- * advertisers.
- */
-int
-node_open(Flavor f, const struct orb_metadata *meta, const void *data, bool advertiser)
-{
- char path[orb_maxpath];
- int fd, ret;
-
- /*
- * If meta is null, the object was not defined, i.e. it is not
- * known to the system. We can't advertise/subscribe such a thing.
- */
- if (nullptr == meta) {
- errno = ENOENT;
- return ERROR;
- }
-
- /*
- * Advertiser must publish an initial value.
- */
- if (advertiser && (data == nullptr)) {
- errno = EINVAL;
- return ERROR;
- }
-
- /*
- * Generate the path to the node and try to open it.
- */
- ret = node_mkpath(path, f, meta);
-
- if (ret != OK) {
- errno = -ret;
- return ERROR;
- }
-
- /* open the path as either the advertiser or the subscriber */
- fd = open(path, (advertiser) ? O_WRONLY : O_RDONLY);
-
- /* we may need to advertise the node... */
- if (fd < 0) {
-
- /* try to create the node */
- ret = node_advertise(meta);
-
- /* on success, try the open again */
- if (ret == OK)
- fd = open(path, (advertiser) ? O_WRONLY : O_RDONLY);
- }
-
- if (fd < 0) {
- errno = EIO;
- return ERROR;
- }
-
- /* everything has been OK, we can return the handle now */
- return fd;
-}
-
-} // namespace
-
-orb_advert_t
-orb_advertise(const struct orb_metadata *meta, const void *data)
-{
- int result, fd;
- orb_advert_t advertiser;
-
- /* open the node as an advertiser */
- fd = node_open(PUBSUB, meta, data, true);
- if (fd == ERROR)
- return ERROR;
-
- /* get the advertiser handle and close the node */
- result = ioctl(fd, ORBIOCGADVERTISER, (unsigned long)&advertiser);
- close(fd);
- if (result == ERROR)
- return ERROR;
-
- /* the advertiser must perform an initial publish to initialise the object */
- result= orb_publish(meta, advertiser, data);
- if (result == ERROR)
- return ERROR;
-
- return advertiser;
-}
-
-int
-orb_subscribe(const struct orb_metadata *meta)
-{
- return node_open(PUBSUB, meta, nullptr, false);
-}
-
-int
-orb_unsubscribe(int handle)
-{
- return close(handle);
-}
-
-int
-orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
-{
- return ORBDevNode::publish(meta, handle, data);
-}
-
-int
-orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
-{
- int ret;
-
- ret = read(handle, buffer, meta->o_size);
-
- if (ret < 0)
- return ERROR;
-
- if (ret != (int)meta->o_size) {
- errno = EIO;
- return ERROR;
- }
-
- return OK;
-}
-
-int
-orb_check(int handle, bool *updated)
-{
- return ioctl(handle, ORBIOCUPDATED, (unsigned long)(uintptr_t)updated);
-}
-
-int
-orb_stat(int handle, uint64_t *time)
-{
- return ioctl(handle, ORBIOCLASTUPDATE, (unsigned long)(uintptr_t)time);
-}
-
-int
-orb_set_interval(int handle, unsigned interval)
-{
- return ioctl(handle, ORBIOCSETINTERVAL, interval * 1000);
-}
-
diff --git a/apps/uORB/uORB.h b/apps/uORB/uORB.h
deleted file mode 100644
index 82ff46ad2..000000000
--- a/apps/uORB/uORB.h
+++ /dev/null
@@ -1,264 +0,0 @@
-/****************************************************************************
- *
- * 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.
- *
- ****************************************************************************/
-
-#ifndef _UORB_UORB_H
-#define _UORB_UORB_H
-
-/**
- * @file uORB.h
- * API for the uORB lightweight object broker.
- */
-
-#include <sys/types.h>
-#include <stdint.h>
-#include <stdbool.h>
-
-// Hack until everything is using this header
-#include <systemlib/visibility.h>
-
-/**
- * Object metadata.
- */
-struct orb_metadata {
- const char *o_name; /**< unique object name */
- const size_t o_size; /**< object size */
-};
-
-typedef const struct orb_metadata *orb_id_t;
-
-/**
- * Generates a pointer to the uORB metadata structure for
- * a given topic.
- *
- * The topic must have been declared previously in scope
- * with ORB_DECLARE().
- *
- * @param _name The name of the topic.
- */
-#define ORB_ID(_name) &__orb_##_name
-
-/**
- * Declare (prototype) the uORB metadata for a topic.
- *
- * Note that optional topics are declared weak; this allows a potential
- * subscriber to attempt to subscribe to a topic that is not known to the
- * system at runtime. The ORB_ID() macro will return NULL/nullptr for
- * such a topic, and attempts to advertise or subscribe to it will
- * return -1/ENOENT (see below).
- *
- * @param _name The name of the topic.
- */
-#if defined(__cplusplus)
-# define ORB_DECLARE(_name) extern "C" const struct orb_metadata __orb_##_name __EXPORT
-# define ORB_DECLARE_OPTIONAL(_name) extern "C" const struct orb_metadata __orb_##_name __EXPORT __attribute__((weak))
-#else
-# define ORB_DECLARE(_name) extern const struct orb_metadata __orb_##_name __EXPORT
-# define ORB_DECLARE_OPTIONAL(_name) extern const struct orb_metadata __orb_##_name __EXPORT __attribute__((weak))
-#endif
-
-/**
- * Define (instantiate) the uORB metadata for a topic.
- *
- * The uORB metadata is used to help ensure that updates and
- * copies are accessing the right data.
- *
- * Note that there must be no more than one instance of this macro
- * for each topic.
- *
- * @param _name The name of the topic.
- * @param _struct The structure the topic provides.
- */
-#define ORB_DEFINE(_name, _struct) \
- const struct orb_metadata __orb_##_name = { \
- #_name, \
- sizeof(_struct) \
- }; struct hack
-
-__BEGIN_DECLS
-
-/**
- * ORB topic advertiser handle.
- *
- * Advertiser handles are global; once obtained they can be shared freely
- * and do not need to be closed or released.
- *
- * This permits publication from interrupt context and other contexts where
- * a file-descriptor-based handle would not otherwise be in scope for the
- * publisher.
- */
-typedef intptr_t orb_advert_t;
-
-/**
- * Advertise as the publisher of a topic.
- *
- * This performs the initial advertisement of a topic; it creates the topic
- * node in /obj if required and publishes the initial data.
- *
- * Any number of advertisers may publish to a topic; publications are atomic
- * but co-ordination between publishers is not provided by the ORB.
- *
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
- * @param data A pointer to the initial data to be published.
- * For topics updated by interrupt handlers, the advertisement
- * must be performed from non-interrupt context.
- * @return ERROR on error, otherwise returns a handle
- * that can be used to publish to the topic.
- * If the topic in question is not known (due to an
- * ORB_DEFINE with no corresponding ORB_DECLARE)
- * this function will return -1 and set errno to ENOENT.
- */
-extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *data) __EXPORT;
-
-/**
- * Publish new data to a topic.
- *
- * The data is atomically published to the topic and any waiting subscribers
- * will be notified. Subscribers that are not waiting can check the topic
- * for updates using orb_check and/or orb_stat.
- *
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
- * @handle The handle returned from orb_advertise.
- * @param data A pointer to the data to be published.
- * @return OK on success, ERROR otherwise with errno set accordingly.
- */
-extern int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data) __EXPORT;
-
-/**
- * Subscribe to a topic.
- *
- * The returned value is a file descriptor that can be passed to poll()
- * in order to wait for updates to a topic, as well as topic_read,
- * orb_check and orb_stat.
- *
- * Subscription will succeed even if the topic has not been advertised;
- * in this case the topic will have a timestamp of zero, it will never
- * signal a poll() event, checking will always return false and it cannot
- * be copied. When the topic is subsequently advertised, poll, check,
- * stat and copy calls will react to the initial publication that is
- * performed as part of the advertisement.
- *
- * Subscription will fail if the topic is not known to the system, i.e.
- * there is nothing in the system that has declared the topic and thus it
- * can never be published.
- *
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
- * @return ERROR on error, otherwise returns a handle
- * that can be used to read and update the topic.
- * If the topic in question is not known (due to an
- * ORB_DEFINE_OPTIONAL with no corresponding ORB_DECLARE)
- * this function will return -1 and set errno to ENOENT.
- */
-extern int orb_subscribe(const struct orb_metadata *meta) __EXPORT;
-
-/**
- * Unsubscribe from a topic.
- *
- * @param handle A handle returned from orb_subscribe.
- * @return OK on success, ERROR otherwise with errno set accordingly.
- */
-extern int orb_unsubscribe(int handle) __EXPORT;
-
-/**
- * Fetch data from a topic.
- *
- * This is the only operation that will reset the internal marker that
- * indicates that a topic has been updated for a subscriber. Once poll
- * or check return indicating that an updaet is available, this call
- * must be used to update the subscription.
- *
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
- * @param handle A handle returned from orb_subscribe.
- * @param buffer Pointer to the buffer receiving the data, or NULL
- * if the caller wants to clear the updated flag without
- * using the data.
- * @return OK on success, ERROR otherwise with errno set accordingly.
- */
-extern int orb_copy(const struct orb_metadata *meta, int handle, void *buffer) __EXPORT;
-
-/**
- * Check whether a topic has been published to since the last orb_copy.
- *
- * This check can be used to determine whether to copy the topic when
- * not using poll(), or to avoid the overhead of calling poll() when the
- * topic is likely to have updated.
- *
- * Updates are tracked on a per-handle basis; this call will continue to
- * return true until orb_copy is called using the same handle. This interface
- * should be preferred over calling orb_stat due to the race window between
- * stat and copy that can lead to missed updates.
- *
- * @param handle A handle returned from orb_subscribe.
- * @param updated Set to true if the topic has been updated since the
- * last time it was copied using this handle.
- * @return OK if the check was successful, ERROR otherwise with
- * errno set accordingly.
- */
-extern int orb_check(int handle, bool *updated) __EXPORT;
-
-/**
- * Return the last time that the topic was updated.
- *
- * @param handle A handle returned from orb_subscribe.
- * @param time Returns the absolute time that the topic was updated, or zero if it has
- * never been updated. Time is measured in microseconds.
- * @return OK on success, ERROR otherwise with errno set accordingly.
- */
-extern int orb_stat(int handle, uint64_t *time) __EXPORT;
-
-/**
- * Set the minimum interval between which updates are seen for a subscription.
- *
- * If this interval is set, the subscriber will not see more than one update
- * within the period.
- *
- * Specifically, the first time an update is reported to the subscriber a timer
- * is started. The update will continue to be reported via poll and orb_check, but
- * once fetched via orb_copy another update will not be reported until the timer
- * expires.
- *
- * This feature can be used to pace a subscriber that is watching a topic that
- * would otherwise update too quickly.
- *
- * @param handle A handle returned from orb_subscribe.
- * @param interval An interval period in milliseconds.
- * @return OK on success, ERROR otherwise with ERRNO set accordingly.
- */
-extern int orb_set_interval(int handle, unsigned interval) __EXPORT;
-
-__END_DECLS
-
-#endif /* _UORB_UORB_H */