Merge remote-tracking branch 'upstream/master'

This commit is contained in:
unknown 2013-08-15 16:35:15 -04:00
commit 5142a9ffda
20 changed files with 99 additions and 45 deletions

5
.gitignore vendored
View File

@ -24,4 +24,7 @@ Firmware.sublime-workspace
Images/*.bin
Images/*.px4
mavlink/include/mavlink/v0.9/
NuttX
/NuttX
/Documentation/doxy.log
/Documentation/html/
/Documentation/doxygen*objdb*tmp

View File

@ -569,7 +569,7 @@ WARN_LOGFILE = doxy.log
# directories like "/usr/src/myproject". Separate the files or directories
# with spaces.
INPUT = ../apps
INPUT = ../src
# This tag can be used to specify the character encoding of the source files
# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is
@ -599,9 +599,8 @@ RECURSIVE = YES
# excluded from the INPUT source files. This way you can easily exclude a
# subdirectory from a directory tree whose root is specified with the INPUT tag.
EXCLUDE = ../dist/ \
../docs/html/ \
html
EXCLUDE = ../src/modules/mathlib/CMSIS \
../src/modules/attitude_estimator_ekf/codegen
# The EXCLUDE_SYMLINKS tag can be used select whether or not files or
# directories that are symbolic links (a Unix filesystem feature) are excluded

View File

@ -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>

View File

@ -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);

View File

@ -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);

View File

@ -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);

View File

@ -47,6 +47,7 @@
/**
* @addtogroup topics
* @{
*/
/**

View File

@ -51,10 +51,6 @@
#include <stdbool.h>
#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
{

View File

@ -46,11 +46,6 @@
#include <stdbool.h>
#include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
enum NAV_CMD {
NAV_CMD_WAYPOINT = 0,
NAV_CMD_LOITER_TURN_COUNT,
@ -61,6 +56,11 @@ enum NAV_CMD {
NAV_CMD_TAKEOFF
};
/**
* @addtogroup topics
* @{
*/
/**
* Global position setpoint in WGS84 coordinates.
*

View File

@ -43,11 +43,6 @@
#include <stdint.h>
#include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
/**
* Off-board control inputs.
*
@ -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;

View File

@ -46,6 +46,7 @@
/**
* @addtogroup topics
* @{
*/
/**

View File

@ -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

View File

@ -45,11 +45,6 @@
#include <stdint.h>
#include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
/**
* The number of RC channel inputs supported.
* Current (Q1/2013) radios support up to 18 channels,
@ -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. */

View File

@ -46,17 +46,17 @@
#include <stdbool.h>
#include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
enum MAGNETOMETER_MODE {
MAGNETOMETER_MODE_NORMAL = 0,
MAGNETOMETER_MODE_POSITIVE_BIAS,
MAGNETOMETER_MODE_NEGATIVE_BIAS
};
/**
* @addtogroup topics
* @{
*/
/**
* Sensor readings in raw and SI-unit form.
*

View File

@ -50,10 +50,6 @@
#include <stdbool.h>
#include "../uORB.h"
/**
* @addtogroup topics
*/
enum SUBSYSTEM_TYPE
{
SUBSYSTEM_TYPE_GYRO = 1,
@ -75,6 +71,10 @@ enum SUBSYSTEM_TYPE
SUBSYSTEM_TYPE_RANGEFINDER = 131072
};
/**
* @addtogroup topics
*/
/**
* State of individual sub systems
*/

View File

@ -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 */

View File

@ -48,6 +48,7 @@
/**
* @addtogroup topics
* @{
*/
/**

View File

@ -45,11 +45,6 @@
#include <stdint.h>
#include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
/**
* Commands for commander app.
*
@ -110,6 +105,10 @@ enum VEHICLE_CMD_RESULT
VEHICLE_CMD_RESULT_ENUM_END=5, /* | */
};
/**
* @addtogroup topics
* @{
*/
struct vehicle_command_s
{

View File

@ -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;

View File

@ -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.