aboutsummaryrefslogtreecommitdiff
path: root/src/modules/uORB
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/uORB')
-rw-r--r--src/modules/uORB/Publication.cpp8
-rw-r--r--src/modules/uORB/Publication.hpp96
-rw-r--r--src/modules/uORB/Subscription.cpp20
-rw-r--r--src/modules/uORB/Subscription.hpp117
-rw-r--r--src/modules/uORB/topics/actuator_armed.h69
-rw-r--r--src/modules/uORB/topics/actuator_controls.h82
-rw-r--r--src/modules/uORB/topics/airspeed.h2
-rw-r--r--src/modules/uORB/topics/fence.h2
-rw-r--r--src/modules/uORB/topics/manual_control_setpoint.h111
-rw-r--r--src/modules/uORB/topics/parameter_update.h61
-rw-r--r--src/modules/uORB/topics/rc_channels.h99
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h91
-rw-r--r--src/modules/uORB/topics/vehicle_attitude_setpoint.h89
-rw-r--r--src/modules/uORB/topics/vehicle_control_mode.h95
-rw-r--r--src/modules/uORB/topics/vehicle_global_position.h2
-rw-r--r--src/modules/uORB/topics/vehicle_rates_setpoint.h68
-rw-r--r--src/modules/uORB/topics/vehicle_status.h263
-rw-r--r--src/modules/uORB/uORB.h30
18 files changed, 222 insertions, 1083 deletions
diff --git a/src/modules/uORB/Publication.cpp b/src/modules/uORB/Publication.cpp
index 71757e1f4..41a866968 100644
--- a/src/modules/uORB/Publication.cpp
+++ b/src/modules/uORB/Publication.cpp
@@ -49,15 +49,16 @@
#include "topics/actuator_direct.h"
#include "topics/encoders.h"
#include "topics/tecs_status.h"
+#include "topics/rc_channels.h"
namespace uORB {
template<class T>
Publication<T>::Publication(
- List<PublicationBase *> * list,
- const struct orb_metadata *meta) :
+ const struct orb_metadata *meta,
+ List<PublicationNode *> * list) :
T(), // initialize data structure to zero
- PublicationBase(list, meta) {
+ PublicationNode(meta, list) {
}
template<class T>
@@ -80,5 +81,6 @@ template class __EXPORT Publication<actuator_outputs_s>;
template class __EXPORT Publication<actuator_direct_s>;
template class __EXPORT Publication<encoders_s>;
template class __EXPORT Publication<tecs_status_s>;
+template class __EXPORT Publication<rc_channels_s>;
}
diff --git a/src/modules/uORB/Publication.hpp b/src/modules/uORB/Publication.hpp
index 8650b3df8..fd1ee4dec 100644
--- a/src/modules/uORB/Publication.hpp
+++ b/src/modules/uORB/Publication.hpp
@@ -38,6 +38,8 @@
#pragma once
+#include <assert.h>
+
#include <uORB/uORB.h>
#include <containers/List.hpp>
@@ -49,55 +51,112 @@ namespace uORB
* Base publication warapper class, used in list traversal
* of various publications.
*/
-class __EXPORT PublicationBase : public ListNode<uORB::PublicationBase *>
+class __EXPORT PublicationBase
{
public:
- PublicationBase(
- List<PublicationBase *> * list,
- const struct orb_metadata *meta) :
+ /**
+ * Constructor
+ *
+ *
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ */
+ PublicationBase(const struct orb_metadata *meta) :
_meta(meta),
_handle(-1) {
- if (list != NULL) list->add(this);
}
- void update() {
+
+ /**
+ * Update the struct
+ * @param data The uORB message struct we are updating.
+ */
+ void update(void * data) {
if (_handle > 0) {
- orb_publish(getMeta(), getHandle(), getDataVoidPtr());
+ orb_publish(getMeta(), getHandle(), data);
} else {
- setHandle(orb_advertise(getMeta(), getDataVoidPtr()));
+ setHandle(orb_advertise(getMeta(), data));
}
}
- virtual void *getDataVoidPtr() = 0;
+
+ /**
+ * Deconstructor
+ */
virtual ~PublicationBase() {
orb_unsubscribe(getHandle());
}
+// accessors
const struct orb_metadata *getMeta() { return _meta; }
int getHandle() { return _handle; }
protected:
+// accessors
void setHandle(orb_advert_t handle) { _handle = handle; }
+// attributes
const struct orb_metadata *_meta;
orb_advert_t _handle;
};
/**
+ * alias class name so it is clear that the base class
+ * can be used by itself if desired
+ */
+typedef PublicationBase PublicationTiny;
+
+/**
+ * The publication base class as a list node.
+ */
+class __EXPORT PublicationNode :
+ public PublicationBase,
+ public ListNode<PublicationNode *>
+{
+public:
+ /**
+ * Constructor
+ *
+ *
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ * @param list A pointer to a list of subscriptions
+ * that this should be appended to.
+ */
+ PublicationNode(const struct orb_metadata *meta,
+ List<PublicationNode *> * list=nullptr) :
+ PublicationBase(meta) {
+ if (list != nullptr) list->add(this);
+ }
+
+ /**
+ * This function is the callback for list traversal
+ * updates, a child class must implement it.
+ */
+ virtual void update() = 0;
+};
+
+/**
* Publication wrapper class
*/
template<class T>
class Publication :
public T, // this must be first!
- public PublicationBase
+ public PublicationNode
{
public:
/**
* Constructor
*
- * @param list A list interface for adding to list during construction
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
+ * @param meta The uORB metadata (usually from
+ * the ORB_ID() macro) for the topic.
+ * @param list A list interface for adding to
+ * list during construction
*/
- Publication(List<PublicationBase *> * list,
- const struct orb_metadata *meta);
+ Publication(const struct orb_metadata *meta,
+ List<PublicationNode *> * list=nullptr);
+
+ /**
+ * Deconstructor
+ **/
virtual ~Publication();
+
/*
* XXX
* This function gets the T struct, assuming
@@ -106,6 +165,13 @@ public:
* seem to be available
*/
void *getDataVoidPtr();
+
+ /**
+ * Create an update function that uses the embedded struct.
+ */
+ void update() {
+ PublicationBase::update(getDataVoidPtr());
+ }
};
} // namespace uORB
diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp
index 44b6debc7..fa0594c2e 100644
--- a/src/modules/uORB/Subscription.cpp
+++ b/src/modules/uORB/Subscription.cpp
@@ -52,25 +52,18 @@
#include "topics/vehicle_local_position.h"
#include "topics/vehicle_attitude_setpoint.h"
#include "topics/vehicle_rates_setpoint.h"
+#include "topics/rc_channels.h"
namespace uORB
{
-bool __EXPORT SubscriptionBase::updated()
-{
- bool isUpdated = false;
- orb_check(_handle, &isUpdated);
- return isUpdated;
-}
-
template<class T>
Subscription<T>::Subscription(
- List<SubscriptionBase *> * list,
- const struct orb_metadata *meta, unsigned interval) :
+ const struct orb_metadata *meta,
+ unsigned interval,
+ List<SubscriptionNode *> * list) :
T(), // initialize data structure to zero
- SubscriptionBase(list, meta) {
- setHandle(orb_subscribe(getMeta()));
- orb_set_interval(getHandle(), interval);
+ SubscriptionNode(meta, interval, list) {
}
template<class T>
@@ -101,5 +94,8 @@ template class __EXPORT Subscription<vehicle_local_position_setpoint_s>;
template class __EXPORT Subscription<vehicle_local_position_s>;
template class __EXPORT Subscription<vehicle_attitude_setpoint_s>;
template class __EXPORT Subscription<vehicle_rates_setpoint_s>;
+template class __EXPORT Subscription<rc_channels_s>;
+template class __EXPORT Subscription<vehicle_control_mode_s>;
+template class __EXPORT Subscription<actuator_armed_s>;
} // namespace uORB
diff --git a/src/modules/uORB/Subscription.hpp b/src/modules/uORB/Subscription.hpp
index 34e9a83e0..f82586285 100644
--- a/src/modules/uORB/Subscription.hpp
+++ b/src/modules/uORB/Subscription.hpp
@@ -38,10 +38,11 @@
#pragma once
+#include <assert.h>
+
#include <uORB/uORB.h>
#include <containers/List.hpp>
-
namespace uORB
{
@@ -49,8 +50,7 @@ namespace uORB
* Base subscription warapper class, used in list traversal
* of various subscriptions.
*/
-class __EXPORT SubscriptionBase :
- public ListNode<SubscriptionBase *>
+class __EXPORT SubscriptionBase
{
public:
// methods
@@ -58,23 +58,42 @@ public:
/**
* Constructor
*
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ *
+ * @param interval The minimum interval in milliseconds
+ * between updates
*/
- SubscriptionBase(
- List<SubscriptionBase *> * list,
- const struct orb_metadata *meta) :
+ SubscriptionBase(const struct orb_metadata *meta,
+ unsigned interval=0) :
_meta(meta),
_handle() {
- if (list != NULL) list->add(this);
+ setHandle(orb_subscribe(getMeta()));
+ orb_set_interval(getHandle(), interval);
}
- bool updated();
- void update() {
+
+ /**
+ * Check if there is a new update.
+ * */
+ bool updated() {
+ bool isUpdated = false;
+ orb_check(_handle, &isUpdated);
+ return isUpdated;
+ }
+
+ /**
+ * Update the struct
+ * @param data The uORB message struct we are updating.
+ */
+ void update(void * data) {
if (updated()) {
- orb_copy(_meta, _handle, getDataVoidPtr());
+ orb_copy(_meta, _handle, data);
}
}
- virtual void *getDataVoidPtr() = 0;
+
+ /**
+ * Deconstructor
+ */
virtual ~SubscriptionBase() {
orb_unsubscribe(_handle);
}
@@ -90,30 +109,86 @@ protected:
};
/**
+ * alias class name so it is clear that the base class
+ */
+typedef SubscriptionBase SubscriptionTiny;
+
+/**
+ * The publication base class as a list node.
+ */
+class __EXPORT SubscriptionNode :
+
+ public SubscriptionBase,
+ public ListNode<SubscriptionNode *>
+{
+public:
+ /**
+ * Constructor
+ *
+ *
+ * @param meta The uORB metadata (usually from the ORB_ID()
+ * macro) for the topic.
+ * @param interval The minimum interval in milliseconds
+ * between updates
+ * @param list A pointer to a list of subscriptions
+ * that this should be appended to.
+ */
+ SubscriptionNode(const struct orb_metadata *meta,
+ unsigned interval=0,
+ List<SubscriptionNode *> * list=nullptr) :
+ SubscriptionBase(meta, interval),
+ _interval(interval) {
+ if (list != nullptr) list->add(this);
+ }
+
+ /**
+ * This function is the callback for list traversal
+ * updates, a child class must implement it.
+ */
+ virtual void update() = 0;
+// accessors
+ unsigned getInterval() { return _interval; }
+protected:
+// attributes
+ unsigned _interval;
+
+};
+
+/**
* Subscription wrapper class
*/
template<class T>
class __EXPORT Subscription :
public T, // this must be first!
- public SubscriptionBase
+ public SubscriptionNode
{
public:
/**
* Constructor
*
- * @param list A list interface for adding to list during construction
- * @param meta The uORB metadata (usually from the ORB_ID() macro)
- * for the topic.
- * @param interval The minimum interval in milliseconds between updates
+ * @param meta The uORB metadata (usually from
+ * the ORB_ID() macro) for the topic.
+ * @param interval The minimum interval in milliseconds
+ * between updates
+ * @param list A list interface for adding to
+ * list during construction
*/
- Subscription(
- List<SubscriptionBase *> * list,
- const struct orb_metadata *meta, unsigned interval);
+ Subscription(const struct orb_metadata *meta,
+ unsigned interval=0,
+ List<SubscriptionNode *> * list=nullptr);
/**
* Deconstructor
*/
virtual ~Subscription();
+
+ /**
+ * Create an update function that uses the embedded struct.
+ */
+ void update() {
+ SubscriptionBase::update(getDataVoidPtr());
+ }
+
/*
* XXX
* This function gets the T struct, assuming
diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h
deleted file mode 100644
index 0f6c9aca1..000000000
--- a/src/modules/uORB/topics/actuator_armed.h
+++ /dev/null
@@ -1,69 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 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 actuator_armed.h
- *
- * Actuator armed topic
- *
- */
-
-#ifndef TOPIC_ACTUATOR_ARMED_H
-#define TOPIC_ACTUATOR_ARMED_H
-
-#include <stdint.h>
-#include "../uORB.h"
-
-/**
- * @addtogroup topics
- * @{
- */
-
-/** global 'actuator output is live' control. */
-struct actuator_armed_s {
-
- uint64_t timestamp; /**< Microseconds since system boot */
- bool armed; /**< Set to true if system is armed */
- bool ready_to_arm; /**< Set to true if system is ready to be armed */
- bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */
- bool force_failsafe; /**< Set to true if the actuators are forced to the failsafe position */
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(actuator_armed);
-
-#endif
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
deleted file mode 100644
index 668f8f164..000000000
--- a/src/modules/uORB/topics/actuator_controls.h
+++ /dev/null
@@ -1,82 +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 */
-
-/* control sets with pre-defined applications */
-#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
-
-/**
- * @addtogroup topics
- * @{
- */
-
-struct actuator_controls_s {
- uint64_t timestamp;
- uint64_t timestamp_sample; /**< the timestamp the data this control response is based on was sampled */
- 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);
-ORB_DECLARE(actuator_controls_virtual_mc);
-ORB_DECLARE(actuator_controls_virtual_fw);
-
-
-#endif
diff --git a/src/modules/uORB/topics/airspeed.h b/src/modules/uORB/topics/airspeed.h
index d2ee754cd..676c37c77 100644
--- a/src/modules/uORB/topics/airspeed.h
+++ b/src/modules/uORB/topics/airspeed.h
@@ -40,7 +40,7 @@
#ifndef TOPIC_AIRSPEED_H_
#define TOPIC_AIRSPEED_H_
-#include "../uORB.h"
+#include <platforms/px4_defines.h>
#include <stdint.h>
/**
diff --git a/src/modules/uORB/topics/fence.h b/src/modules/uORB/topics/fence.h
index 6f16c51cf..a61f078ba 100644
--- a/src/modules/uORB/topics/fence.h
+++ b/src/modules/uORB/topics/fence.h
@@ -42,7 +42,7 @@
#include <stdint.h>
#include <stdbool.h>
-#include "../uORB.h"
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h
deleted file mode 100644
index 50b7bd9e5..000000000
--- a/src/modules/uORB/topics/manual_control_setpoint.h
+++ /dev/null
@@ -1,111 +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"
-
-/**
- * Switch position
- */
-typedef enum {
- SWITCH_POS_NONE = 0, /**< switch is not mapped */
- SWITCH_POS_ON, /**< switch activated (value = 1) */
- SWITCH_POS_MIDDLE, /**< middle position (value = 0) */
- SWITCH_POS_OFF /**< switch not activated (value = -1) */
-} switch_pos_t;
-
-/**
- * @addtogroup topics
- * @{
- */
-
-struct manual_control_setpoint_s {
- uint64_t timestamp;
-
- /**
- * Any of the channels may not be available and be set to NaN
- * to indicate that it does not contain valid data.
- * The variable names follow the definition of the
- * MANUAL_CONTROL mavlink message.
- * The default range is from -1 to 1 (mavlink message -1000 to 1000)
- * The range for the z variable is defined from 0 to 1. (The z field of
- * the MANUAL_CONTROL mavlink message is defined from -1000 to 1000)
- */
- float x; /**< stick position in x direction -1..1
- in general corresponds to forward/back motion or pitch of vehicle,
- in general a positive value means forward or negative pitch and
- a negative value means backward or positive pitch */
- float y; /**< stick position in y direction -1..1
- in general corresponds to right/left motion or roll of vehicle,
- in general a positive value means right or positive roll and
- a negative value means left or negative roll */
- float z; /**< throttle stick position 0..1
- in general corresponds to up/down motion or thrust of vehicle,
- in general the value corresponds to the demanded throttle by the user,
- if the input is used for setting the setpoint of a vertical position
- controller any value > 0.5 means up and any value < 0.5 means down */
- float r; /**< yaw stick/twist positon, -1..1
- in general corresponds to the righthand rotation around the vertical
- (downwards) axis of the vehicle */
- 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 */
-
- switch_pos_t mode_switch; /**< main mode 3 position switch (mandatory): _MANUAL_, ASSIST, AUTO */
- switch_pos_t return_switch; /**< return to launch 2 position switch (mandatory): _NORMAL_, RTL */
- switch_pos_t posctl_switch; /**< position control 2 position switch (optional): _ALTCTL_, POSCTL */
- switch_pos_t loiter_switch; /**< loiter 2 position switch (optional): _MISSION_, LOITER */
- switch_pos_t acro_switch; /**< acro 2 position switch (optional): _MANUAL_, ACRO */
- switch_pos_t offboard_switch; /**< offboard 2 position switch (optional): _NORMAL_, OFFBOARD */
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(manual_control_setpoint);
-
-#endif
diff --git a/src/modules/uORB/topics/parameter_update.h b/src/modules/uORB/topics/parameter_update.h
deleted file mode 100644
index 68964deb0..000000000
--- a/src/modules/uORB/topics/parameter_update.h
+++ /dev/null
@@ -1,61 +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"
-
-/**
- * @addtogroup topics
- * @{
- */
-
-struct parameter_update_s {
- /** time at which the latest parameter was updated */
- uint64_t timestamp;
-};
-
-/**
- * @}
- */
-
-ORB_DECLARE(parameter_update);
-
-#endif \ No newline at end of file
diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h
deleted file mode 100644
index 2fde5d424..000000000
--- a/src/modules/uORB/topics/rc_channels.h
+++ /dev/null
@@ -1,99 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file rc_channels.h
- * Definition of the rc_channels uORB topic.
- *
- * @deprecated DO NOT USE FOR NEW CODE
- */
-
-#ifndef RC_CHANNELS_H_
-#define RC_CHANNELS_H_
-
-#include <stdint.h>
-#include "../uORB.h"
-
-/**
- * This defines the mapping of the RC functions.
- * The value assigned to the specific function corresponds to the entry of
- * the channel array channels[].
- */
-enum RC_CHANNELS_FUNCTION {
- THROTTLE = 0,
- ROLL,
- PITCH,
- YAW,
- MODE,
- RETURN,
- POSCTL,
- LOITER,
- OFFBOARD,
- ACRO,
- FLAPS,
- AUX_1,
- AUX_2,
- AUX_3,
- AUX_4,
- AUX_5,
- PARAM_1,
- PARAM_2,
- PARAM_3
-};
-
-// MAXIMUM FUNCTIONS IS != MAXIMUM RC INPUT CHANNELS
-
-#define RC_CHANNELS_FUNCTION_MAX 19
-
-/**
- * @addtogroup topics
- * @{
- */
-struct rc_channels_s {
- uint64_t timestamp; /**< Timestamp in microseconds since boot time */
- uint64_t timestamp_last_valid; /**< Timestamp of last valid RC signal */
- float channels[RC_CHANNELS_FUNCTION_MAX]; /**< Scaled to -1..1 (throttle: 0..1) */
- uint8_t channel_count; /**< Number of valid channels */
- int8_t function[RC_CHANNELS_FUNCTION_MAX]; /**< Functions mapping */
- uint8_t rssi; /**< Receive signal strength index */
- bool signal_lost; /**< Control signal lost, should be checked together with topic timeout */
-}; /**< radio control channels. */
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(rc_channels);
-
-#endif
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
deleted file mode 100755
index 019944dc0..000000000
--- a/src/modules/uORB/topics/vehicle_attitude.h
+++ /dev/null
@@ -1,91 +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) */
- float g_comp[3]; /**< Compensated gravity vector */
- bool R_valid; /**< Rotation matrix valid */
- bool q_valid; /**< Quaternion valid */
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(vehicle_attitude);
-
-#endif
diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h
deleted file mode 100644
index 1cfc37cc6..000000000
--- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h
+++ /dev/null
@@ -1,89 +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[3][3]; /**< Rotation matrix describing the setpoint as rotation from the current body frame */
- bool R_valid; /**< Set to true if rotation matrix is valid */
-
- //! For quaternion-based attitude control
- float q_d[4]; /** Desired quaternion for quaternion control */
- bool q_d_valid; /**< Set to true if quaternion vector is valid */
- float q_e[4]; /** Attitude error in quaternion */
- bool q_e_valid; /**< Set to true if quaternion error vector is valid */
-
- float thrust; /**< Thrust in Newton the power system should generate */
-
- bool roll_reset_integral; /**< Reset roll integral part (navigation logic change) */
- bool pitch_reset_integral; /**< Reset pitch integral part (navigation logic change) */
- bool yaw_reset_integral; /**< Reset yaw integral part (navigation logic change) */
-
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(vehicle_attitude_setpoint);
-ORB_DECLARE(mc_virtual_attitude_setpoint);
-ORB_DECLARE(fw_virtual_attitude_setpoint);
-
-#endif /* TOPIC_ARDRONE_CONTROL_H_ */
diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h
deleted file mode 100644
index ca7705456..000000000
--- a/src/modules/uORB/topics/vehicle_control_mode.h
+++ /dev/null
@@ -1,95 +0,0 @@
-/****************************************************************************
- *
- * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @file vehicle_control_mode.h
- * Definition of the vehicle_control_mode uORB topic.
- *
- * All control apps should depend their actions based on the flags set here.
- *
- * @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>
- */
-
-#ifndef VEHICLE_CONTROL_MODE
-#define VEHICLE_CONTROL_MODE
-
-#include <stdint.h>
-#include <stdbool.h>
-#include "../uORB.h"
-#include "vehicle_status.h"
-
-/**
- * @addtogroup topics @{
- */
-
-
-/**
- * state machine / state of vehicle.
- *
- * Encodes the complete system state and is set by the commander app.
- */
-
-struct vehicle_control_mode_s {
- uint64_t timestamp; /**< in microseconds since system start, is set whenever the writing thread stores new data */
-
- bool flag_armed;
-
- bool flag_external_manual_override_ok; /**< external override non-fatal for system. Only true for fixed wing */
-
- // XXX needs yet to be set by state machine helper
- bool flag_system_hil_enabled;
-
- bool flag_control_manual_enabled; /**< true if manual input is mixed in */
- bool flag_control_auto_enabled; /**< true if onboard autopilot should act */
- bool flag_control_offboard_enabled; /**< true if offboard control should be used */
- bool flag_control_rates_enabled; /**< true if rates are stabilized */
- bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */
- bool flag_control_force_enabled; /**< true if force control is mixed in */
- bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */
- bool flag_control_position_enabled; /**< true if position is controlled */
- bool flag_control_altitude_enabled; /**< true if altitude is controlled */
- bool flag_control_climb_rate_enabled; /**< true if climb rate is controlled */
- bool flag_control_termination_enabled; /**< true if flighttermination is enabled */
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(vehicle_control_mode);
-
-#endif
diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h
index bc7046690..137c86dd5 100644
--- a/src/modules/uORB/topics/vehicle_global_position.h
+++ b/src/modules/uORB/topics/vehicle_global_position.h
@@ -45,7 +45,7 @@
#include <stdint.h>
#include <stdbool.h>
-#include "../uORB.h"
+#include <platforms/px4_defines.h>
/**
* @addtogroup topics
diff --git a/src/modules/uORB/topics/vehicle_rates_setpoint.h b/src/modules/uORB/topics/vehicle_rates_setpoint.h
deleted file mode 100644
index 47d51f199..000000000
--- a/src/modules/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);
-ORB_DECLARE(mc_virtual_rates_setpoint);
-ORB_DECLARE(fw_virtual_rates_setpoint);
-#endif
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
deleted file mode 100644
index b56e81e04..000000000
--- a/src/modules/uORB/topics/vehicle_status.h
+++ /dev/null
@@ -1,263 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 - 2014 PX4 Development Team. All rights reserved.
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name PX4 nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/**
- * @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)
- *
- * @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 <julian@oes.ch>
- */
-
-#ifndef VEHICLE_STATUS_H_
-#define VEHICLE_STATUS_H_
-
-#include <stdint.h>
-#include <stdbool.h>
-#include "../uORB.h"
-
-/**
- * @addtogroup topics @{
- */
-
-/**
- * Main state, i.e. what user wants. Controlled by RC or from ground station via telemetry link.
- */
-typedef enum {
- MAIN_STATE_MANUAL = 0,
- MAIN_STATE_ALTCTL,
- MAIN_STATE_POSCTL,
- MAIN_STATE_AUTO_MISSION,
- MAIN_STATE_AUTO_LOITER,
- MAIN_STATE_AUTO_RTL,
- MAIN_STATE_ACRO,
- MAIN_STATE_OFFBOARD,
- MAIN_STATE_MAX
-} main_state_t;
-
-// If you change the order, add or remove arming_state_t states make sure to update the arrays
-// in state_machine_helper.cpp as well.
-typedef enum {
- ARMING_STATE_INIT = 0,
- ARMING_STATE_STANDBY,
- ARMING_STATE_ARMED,
- ARMING_STATE_ARMED_ERROR,
- ARMING_STATE_STANDBY_ERROR,
- ARMING_STATE_REBOOT,
- ARMING_STATE_IN_AIR_RESTORE,
- ARMING_STATE_MAX,
-} arming_state_t;
-
-typedef enum {
- HIL_STATE_OFF = 0,
- HIL_STATE_ON
-} hil_state_t;
-
-/**
- * Navigation state, i.e. "what should vehicle do".
- */
-typedef enum {
- NAVIGATION_STATE_MANUAL = 0, /**< Manual mode */
- NAVIGATION_STATE_ALTCTL, /**< Altitude control mode */
- NAVIGATION_STATE_POSCTL, /**< Position control mode */
- NAVIGATION_STATE_AUTO_MISSION, /**< Auto mission mode */
- NAVIGATION_STATE_AUTO_LOITER, /**< Auto loiter mode */
- NAVIGATION_STATE_AUTO_RTL, /**< Auto return to launch mode */
- NAVIGATION_STATE_AUTO_RCRECOVER, /**< RC recover mode */
- NAVIGATION_STATE_AUTO_RTGS, /**< Auto return to groundstation on data link loss */
- NAVIGATION_STATE_AUTO_LANDENGFAIL, /**< Auto land on engine failure */
- NAVIGATION_STATE_AUTO_LANDGPSFAIL, /**< Auto land on gps failure (e.g. open loop loiter down) */
- NAVIGATION_STATE_ACRO, /**< Acro mode */
- NAVIGATION_STATE_LAND, /**< Land mode */
- NAVIGATION_STATE_DESCEND, /**< Descend mode (no position control) */
- NAVIGATION_STATE_TERMINATION, /**< Termination mode */
- NAVIGATION_STATE_OFFBOARD,
- NAVIGATION_STATE_MAX,
-} navigation_state_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 */
-
-/**
- * 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_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */
- VEHICLE_TYPE_VTOL_DUOROTOR = 19, /* Vtol with two engines */
- VEHICLE_TYPE_VTOL_QUADROTOR = 20, /* Vtol with four engines*/
- VEHICLE_TYPE_ENUM_END = 21 /* | */
-};
-
-enum VEHICLE_BATTERY_WARNING {
- VEHICLE_BATTERY_WARNING_NONE = 0, /**< no battery low voltage warning active */
- VEHICLE_BATTERY_WARNING_LOW, /**< warning of low voltage */
- VEHICLE_BATTERY_WARNING_CRITICAL /**< alerting of critical voltage */
-};
-
-/**
- * @addtogroup topics
- * @{
- */
-
-/**
- * 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 */
-
- main_state_t main_state; /**< main state machine */
- navigation_state_t nav_state; /**< set navigation state machine to specified value */
- arming_state_t arming_state; /**< current arming state */
- hil_state_t hil_state; /**< current hil state */
- bool failsafe; /**< true if system is in failsafe state */
-
- 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 */
-
- bool is_rotary_wing; /**< True if system is in rotary wing configuration, so for a VTOL
- this is only true while flying as a multicopter */
- bool is_vtol; /**< True if the system is VTOL capable */
-
- bool vtol_fw_permanent_stab; /**< True if vtol should stabilize attitude for fw in manual mode */
-
- bool condition_battery_voltage_valid;
- bool condition_system_in_air_restore; /**< true if we can restore in mid air */
- bool condition_system_sensors_initialized;
- bool condition_system_returned_to_home;
- bool condition_auto_mission_available;
- bool condition_global_position_valid; /**< set to true by the commander app if the quality of the position estimate is good enough to use it for navigation */
- bool condition_launch_position_valid; /**< indicates a valid launch position */
- bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */
- bool condition_local_position_valid;
- bool condition_local_altitude_valid;
- bool condition_airspeed_valid; /**< set to true by the commander app if there is a valid airspeed measurement available */
- bool condition_landed; /**< true if vehicle is landed, always true if disarmed */
- bool condition_power_input_valid; /**< set if input power is valid */
- float avionics_power_rail_voltage; /**< voltage of the avionics power rail */
-
- bool rc_signal_found_once;
- bool rc_signal_lost; /**< true if RC reception lost */
- uint64_t rc_signal_lost_timestamp; /**< Time at which the RC reception was lost */
- bool rc_signal_lost_cmd; /**< true if RC lost mode is commanded */
- bool rc_input_blocked; /**< set if RC input should be ignored */
-
- bool data_link_lost; /**< datalink to GCS lost */
- bool data_link_lost_cmd; /**< datalink to GCS lost mode commanded */
- uint8_t data_link_lost_counter; /**< counts unique data link lost events */
- bool engine_failure; /** Set to true if an engine failure is detected */
- bool engine_failure_cmd; /** Set to true if an engine failure mode is commanded */
- bool gps_failure; /** Set to true if a gps failure is detected */
- bool gps_failure_cmd; /** Set to true if a gps failure mode is commanded */
-
- bool barometer_failure; /** Set to true if a barometer failure is detected */
-
- bool offboard_control_signal_found_once;
- bool offboard_control_signal_lost;
- bool offboard_control_signal_weak;
- uint64_t offboard_control_signal_lost_interval; /**< interval in microseconds without an offboard control message */
- bool offboard_control_set_by_command; /**< true if the offboard mode was set by a mavlink command
- and should not be overridden by RC */
-
- /* see SYS_STATUS mavlink message for the following */
- uint32_t onboard_control_sensors_present;
- uint32_t onboard_control_sensors_enabled;
- uint32_t onboard_control_sensors_health;
-
- float load; /**< processor load from 0 to 1 */
- float battery_voltage;
- float battery_current;
- 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 circuit_breaker_engaged_power_check;
- bool circuit_breaker_engaged_airspd_check;
- bool circuit_breaker_engaged_enginefailure_check;
- bool circuit_breaker_engaged_gpsfailure_check;
-};
-
-/**
- * @}
- */
-
-/* register this as object request broker structure */
-ORB_DECLARE(vehicle_status);
-
-#endif
diff --git a/src/modules/uORB/uORB.h b/src/modules/uORB/uORB.h
index beb23f61d..f19fbba7c 100644
--- a/src/modules/uORB/uORB.h
+++ b/src/modules/uORB/uORB.h
@@ -152,7 +152,7 @@ typedef intptr_t orb_advert_t;
* 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.
+ * 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.
@@ -288,4 +288,32 @@ extern int orb_set_interval(int handle, unsigned interval) __EXPORT;
__END_DECLS
+/* Diverse uORB header defines */ //XXX: move to better location
+#define ORB_ID_VEHICLE_ATTITUDE_CONTROLS ORB_ID(actuator_controls_0)
+ORB_DECLARE(actuator_controls_0);
+typedef struct actuator_controls_s actuator_controls_0_s;
+ORB_DECLARE(actuator_controls_1);
+typedef struct actuator_controls_s actuator_controls_1_s;
+ORB_DECLARE(actuator_controls_2);
+typedef struct actuator_controls_s actuator_controls_2_s;
+ORB_DECLARE(actuator_controls_3);
+typedef struct actuator_controls_s actuator_controls_3_s;
+ORB_DECLARE(actuator_controls_virtual_mc);
+typedef struct actuator_controls_s actuator_controls_virtual_mc_s;
+ORB_DECLARE(actuator_controls_virtual_fw);
+typedef struct actuator_controls_s actuator_controls_virtual_fw_s;
+ORB_DECLARE(mc_virtual_rates_setpoint);
+typedef struct vehicle_rates_setpoint_s mc_virtual_rates_setpoint_s;
+ORB_DECLARE(fw_virtual_rates_setpoint);
+typedef struct vehicle_rates_setpoint_s fw_virtual_rates_setpoint_s;
+ORB_DECLARE(mc_virtual_attitude_setpoint);
+typedef struct vehicle_attitude_setpoint_s mc_virtual_attitude_setpoint_s;
+ORB_DECLARE(fw_virtual_attitude_setpoint);
+typedef struct vehicle_attitude_setpoint_s fw_virtual_attitude_setpoint_s;
+typedef uint8_t arming_state_t;
+typedef uint8_t main_state_t;
+typedef uint8_t hil_state_t;
+typedef uint8_t navigation_state_t;
+typedef uint8_t switch_pos_t;
+
#endif /* _UORB_UORB_H */