aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.gitignore3
-rw-r--r--src/modules/uORB/objects_common.cpp4
-rw-r--r--src/modules/uORB/topics/actuator_controls.h9
-rw-r--r--src/modules/uORB/topics/actuator_controls_effective.h9
-rw-r--r--src/modules/uORB/topics/actuator_outputs.h9
-rw-r--r--src/modules/uORB/topics/debug_key_value.h1
-rw-r--r--src/modules/uORB/topics/esc_status.h11
-rw-r--r--src/modules/uORB/topics/mission.h10
-rw-r--r--src/modules/uORB/topics/offboard_control_setpoint.h10
-rw-r--r--src/modules/uORB/topics/omnidirectional_flow.h1
-rw-r--r--src/modules/uORB/topics/parameter_update.h9
-rw-r--r--src/modules/uORB/topics/rc_channels.h10
-rw-r--r--src/modules/uORB/topics/sensor_combined.h10
-rw-r--r--src/modules/uORB/topics/subsystem_info.h8
-rw-r--r--src/modules/uORB/topics/telemetry_status.h9
-rwxr-xr-xsrc/modules/uORB/topics/vehicle_attitude.h1
-rw-r--r--src/modules/uORB/topics/vehicle_command.h9
-rw-r--r--src/modules/uORB/topics/vehicle_global_position_set_triplet.h4
-rw-r--r--src/modules/uORB/topics/vehicle_status.h8
19 files changed, 94 insertions, 41 deletions
diff --git a/.gitignore b/.gitignore
index 6ae5baecc..3fdc1bf2a 100644
--- a/.gitignore
+++ b/.gitignore
@@ -26,4 +26,5 @@ Images/*.px4
mavlink/include/mavlink/v0.9/
/NuttX
/Documentation/doxy.log
-/Documentation/html/ \ No newline at end of file
+/Documentation/html/
+/Documentation/doxygen*objdb*tmp \ No newline at end of file
diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp
index ae5fc6c61..301cfa255 100644
--- a/src/modules/uORB/objects_common.cpp
+++ b/src/modules/uORB/objects_common.cpp
@@ -37,6 +37,10 @@
* Common object definitions without a better home.
*/
+/**
+ * @defgroup topics List of all uORB topics.
+ */
+
#include <nuttx/config.h>
#include <drivers/drv_orb_dev.h>
diff --git a/src/modules/uORB/topics/actuator_controls.h b/src/modules/uORB/topics/actuator_controls.h
index b7c4196c0..a27095be5 100644
--- a/src/modules/uORB/topics/actuator_controls.h
+++ b/src/modules/uORB/topics/actuator_controls.h
@@ -52,11 +52,20 @@
#define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
+/**
+ * @addtogroup topics
+ * @{
+ */
+
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);
diff --git a/src/modules/uORB/topics/actuator_controls_effective.h b/src/modules/uORB/topics/actuator_controls_effective.h
index 088c4fc8f..d7b404ad4 100644
--- a/src/modules/uORB/topics/actuator_controls_effective.h
+++ b/src/modules/uORB/topics/actuator_controls_effective.h
@@ -53,11 +53,20 @@
#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
+/**
+ * @addtogroup topics
+ * @{
+ */
+
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);
diff --git a/src/modules/uORB/topics/actuator_outputs.h b/src/modules/uORB/topics/actuator_outputs.h
index bbe429073..30895ca83 100644
--- a/src/modules/uORB/topics/actuator_outputs.h
+++ b/src/modules/uORB/topics/actuator_outputs.h
@@ -52,12 +52,21 @@
#define NUM_ACTUATOR_OUTPUTS 16
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
+/**
+ * @addtogroup topics
+ * @{
+ */
+
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);
diff --git a/src/modules/uORB/topics/debug_key_value.h b/src/modules/uORB/topics/debug_key_value.h
index a9d1b83fd..9253c787d 100644
--- a/src/modules/uORB/topics/debug_key_value.h
+++ b/src/modules/uORB/topics/debug_key_value.h
@@ -47,6 +47,7 @@
/**
* @addtogroup topics
+ * @{
*/
/**
diff --git a/src/modules/uORB/topics/esc_status.h b/src/modules/uORB/topics/esc_status.h
index 00cf59b28..11332d7a7 100644
--- a/src/modules/uORB/topics/esc_status.h
+++ b/src/modules/uORB/topics/esc_status.h
@@ -52,10 +52,6 @@
#include "../uORB.h"
/**
- * @addtogroup topics @{
- */
-
-/**
* The number of ESCs supported.
* Current (Q2/2013) we support 8 ESCs,
*/
@@ -76,7 +72,12 @@ enum ESC_CONNECTION_TYPE {
};
/**
- *
+ * @addtogroup topics
+ * @{
+ */
+
+/**
+ * Electronic speed controller status.
*/
struct esc_status_s
{
diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h
index 253f444b3..978a3383a 100644
--- a/src/modules/uORB/topics/mission.h
+++ b/src/modules/uORB/topics/mission.h
@@ -46,11 +46,6 @@
#include <stdbool.h>
#include "../uORB.h"
-/**
- * @addtogroup topics
- * @{
- */
-
enum NAV_CMD {
NAV_CMD_WAYPOINT = 0,
NAV_CMD_LOITER_TURN_COUNT,
@@ -62,6 +57,11 @@ enum NAV_CMD {
};
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Global position setpoint in WGS84 coordinates.
*
* This is the position the MAV is heading towards. If it of type loiter,
diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h
index 2e895c59c..7901b930a 100644
--- a/src/modules/uORB/topics/offboard_control_setpoint.h
+++ b/src/modules/uORB/topics/offboard_control_setpoint.h
@@ -44,11 +44,6 @@
#include "../uORB.h"
/**
- * @addtogroup topics
- * @{
- */
-
-/**
* Off-board control inputs.
*
* Typically sent by a ground control station / joystick or by
@@ -66,6 +61,11 @@ enum OFFBOARD_CONTROL_MODE
OFFBOARD_CONTROL_MODE_MULTIROTOR_SIMPLE = 7, /**< roll / pitch rotated aligned to the takeoff orientation, throttle stabilized, yaw pos */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct offboard_control_setpoint_s {
uint64_t timestamp;
diff --git a/src/modules/uORB/topics/omnidirectional_flow.h b/src/modules/uORB/topics/omnidirectional_flow.h
index 8f4be3b3f..a6ad8a131 100644
--- a/src/modules/uORB/topics/omnidirectional_flow.h
+++ b/src/modules/uORB/topics/omnidirectional_flow.h
@@ -46,6 +46,7 @@
/**
* @addtogroup topics
+ * @{
*/
/**
diff --git a/src/modules/uORB/topics/parameter_update.h b/src/modules/uORB/topics/parameter_update.h
index 300e895c7..68964deb0 100644
--- a/src/modules/uORB/topics/parameter_update.h
+++ b/src/modules/uORB/topics/parameter_update.h
@@ -42,11 +42,20 @@
#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
index 9dd54df91..e69335b3d 100644
--- a/src/modules/uORB/topics/rc_channels.h
+++ b/src/modules/uORB/topics/rc_channels.h
@@ -46,11 +46,6 @@
#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.
@@ -83,6 +78,11 @@ enum RC_CHANNELS_FUNCTION
RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct rc_channels_s {
uint64_t timestamp; /**< In microseconds since boot time. */
diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h
index 9a76b5182..ad164555e 100644
--- a/src/modules/uORB/topics/sensor_combined.h
+++ b/src/modules/uORB/topics/sensor_combined.h
@@ -46,11 +46,6 @@
#include <stdbool.h>
#include "../uORB.h"
-/**
- * @addtogroup topics
- * @{
- */
-
enum MAGNETOMETER_MODE {
MAGNETOMETER_MODE_NORMAL = 0,
MAGNETOMETER_MODE_POSITIVE_BIAS,
@@ -58,6 +53,11 @@ enum MAGNETOMETER_MODE {
};
/**
+ * @addtogroup topics
+ * @{
+ */
+
+/**
* Sensor readings in raw and SI-unit form.
*
* These values are read from the sensors. Raw values are in sensor-specific units,
diff --git a/src/modules/uORB/topics/subsystem_info.h b/src/modules/uORB/topics/subsystem_info.h
index c415e832e..cfe0bf69e 100644
--- a/src/modules/uORB/topics/subsystem_info.h
+++ b/src/modules/uORB/topics/subsystem_info.h
@@ -50,10 +50,6 @@
#include <stdbool.h>
#include "../uORB.h"
-/**
- * @addtogroup topics
- */
-
enum SUBSYSTEM_TYPE
{
SUBSYSTEM_TYPE_GYRO = 1,
@@ -76,6 +72,10 @@ enum SUBSYSTEM_TYPE
};
/**
+ * @addtogroup topics
+ */
+
+/**
* State of individual sub systems
*/
struct subsystem_info_s {
diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h
index f30852de5..828fb31cc 100644
--- a/src/modules/uORB/topics/telemetry_status.h
+++ b/src/modules/uORB/topics/telemetry_status.h
@@ -50,6 +50,11 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
TELEMETRY_STATUS_RADIO_TYPE_WIRE
};
+/**
+ * @addtogroup topics
+ * @{
+ */
+
struct telemetry_status_s {
uint64_t timestamp;
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */
@@ -62,6 +67,10 @@ struct telemetry_status_s {
uint8_t txbuf; /**< how full the tx buffer is as a percentage */
};
+/**
+ * @}
+ */
+
ORB_DECLARE(telemetry_status);
#endif /* TOPIC_TELEMETRY_STATUS_H */ \ No newline at end of file
diff --git a/src/modules/uORB/topics/vehicle_attitude.h b/src/modules/uORB/topics/vehicle_attitude.h
index c31c81d0c..4380a5ee7 100755
--- a/src/modules/uORB/topics/vehicle_attitude.h
+++ b/src/modules/uORB/topics/vehicle_attitude.h
@@ -48,6 +48,7 @@
/**
* @addtogroup topics
+ * @{
*/
/**
diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h
index fac571659..31ff014de 100644
--- a/src/modules/uORB/topics/vehicle_command.h
+++ b/src/modules/uORB/topics/vehicle_command.h
@@ -46,11 +46,6 @@
#include "../uORB.h"
/**
- * @addtogroup topics
- * @{
- */
-
-/**
* Commands for commander app.
*
* Should contain all commands from MAVLink's VEHICLE_CMD ENUM,
@@ -110,6 +105,10 @@ enum VEHICLE_CMD_RESULT
VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
struct vehicle_command_s
{
diff --git a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
index 318abba89..8516b263f 100644
--- a/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
+++ b/src/modules/uORB/topics/vehicle_global_position_set_triplet.h
@@ -60,8 +60,8 @@
*/
struct vehicle_global_position_set_triplet_s
{
- bool previous_valid;
- bool next_valid;
+ bool previous_valid; /**< flag indicating previous position is valid */
+ bool next_valid; /**< flag indicating next position is valid */
struct vehicle_global_position_setpoint_s previous;
struct vehicle_global_position_setpoint_s current;
diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h
index c7c1048f6..94068a9ac 100644
--- a/src/modules/uORB/topics/vehicle_status.h
+++ b/src/modules/uORB/topics/vehicle_status.h
@@ -54,10 +54,6 @@
#include <stdbool.h>
#include "../uORB.h"
-/**
- * @addtogroup topics @{
- */
-
/* State Machine */
typedef enum
{
@@ -137,6 +133,10 @@ enum VEHICLE_BATTERY_WARNING {
VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
};
+/**
+ * @addtogroup topics
+ * @{
+ */
/**
* state machine / state of vehicle.