Browse Source

Hotfix: Fixed Doxygen tags for uORB topics

sbg
Lorenz Meier 12 years ago
parent
commit
74d519d9d0
  1. 3
      .gitignore
  2. 4
      src/modules/uORB/objects_common.cpp
  3. 9
      src/modules/uORB/topics/actuator_controls.h
  4. 9
      src/modules/uORB/topics/actuator_controls_effective.h
  5. 9
      src/modules/uORB/topics/actuator_outputs.h
  6. 1
      src/modules/uORB/topics/debug_key_value.h
  7. 11
      src/modules/uORB/topics/esc_status.h
  8. 10
      src/modules/uORB/topics/mission.h
  9. 10
      src/modules/uORB/topics/offboard_control_setpoint.h
  10. 1
      src/modules/uORB/topics/omnidirectional_flow.h
  11. 9
      src/modules/uORB/topics/parameter_update.h
  12. 10
      src/modules/uORB/topics/rc_channels.h
  13. 10
      src/modules/uORB/topics/sensor_combined.h
  14. 8
      src/modules/uORB/topics/subsystem_info.h
  15. 9
      src/modules/uORB/topics/telemetry_status.h
  16. 1
      src/modules/uORB/topics/vehicle_attitude.h
  17. 9
      src/modules/uORB/topics/vehicle_command.h
  18. 4
      src/modules/uORB/topics/vehicle_global_position_set_triplet.h
  19. 8
      src/modules/uORB/topics/vehicle_status.h

3
.gitignore vendored

@ -26,4 +26,5 @@ Images/*.px4
mavlink/include/mavlink/v0.9/ mavlink/include/mavlink/v0.9/
/NuttX /NuttX
/Documentation/doxy.log /Documentation/doxy.log
/Documentation/html/ /Documentation/html/
/Documentation/doxygen*objdb*tmp

4
src/modules/uORB/objects_common.cpp

@ -37,6 +37,10 @@
* Common object definitions without a better home. * Common object definitions without a better home.
*/ */
/**
* @defgroup topics List of all uORB topics.
*/
#include <nuttx/config.h> #include <nuttx/config.h>
#include <drivers/drv_orb_dev.h> #include <drivers/drv_orb_dev.h>

9
src/modules/uORB/topics/actuator_controls.h

@ -52,11 +52,20 @@
#define NUM_ACTUATOR_CONTROLS 8 #define NUM_ACTUATOR_CONTROLS 8
#define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */ #define NUM_ACTUATOR_CONTROL_GROUPS 4 /**< for sanity checking */
/**
* @addtogroup topics
* @{
*/
struct actuator_controls_s { struct actuator_controls_s {
uint64_t timestamp; uint64_t timestamp;
float control[NUM_ACTUATOR_CONTROLS]; float control[NUM_ACTUATOR_CONTROLS];
}; };
/**
* @}
*/
/* actuator control sets; this list can be expanded as more controllers emerge */ /* actuator control sets; this list can be expanded as more controllers emerge */
ORB_DECLARE(actuator_controls_0); ORB_DECLARE(actuator_controls_0);
ORB_DECLARE(actuator_controls_1); ORB_DECLARE(actuator_controls_1);

9
src/modules/uORB/topics/actuator_controls_effective.h

@ -53,11 +53,20 @@
#define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS #define NUM_ACTUATOR_CONTROLS_EFFECTIVE NUM_ACTUATOR_CONTROLS
#define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */ #define NUM_ACTUATOR_CONTROL_GROUPS_EFFECTIVE NUM_ACTUATOR_CONTROL_GROUPS /**< for sanity checking */
/**
* @addtogroup topics
* @{
*/
struct actuator_controls_effective_s { struct actuator_controls_effective_s {
uint64_t timestamp; uint64_t timestamp;
float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE]; float control_effective[NUM_ACTUATOR_CONTROLS_EFFECTIVE];
}; };
/**
* @}
*/
/* actuator control sets; this list can be expanded as more controllers emerge */ /* actuator control sets; this list can be expanded as more controllers emerge */
ORB_DECLARE(actuator_controls_effective_0); ORB_DECLARE(actuator_controls_effective_0);
ORB_DECLARE(actuator_controls_effective_1); ORB_DECLARE(actuator_controls_effective_1);

9
src/modules/uORB/topics/actuator_outputs.h

@ -52,12 +52,21 @@
#define NUM_ACTUATOR_OUTPUTS 16 #define NUM_ACTUATOR_OUTPUTS 16
#define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */ #define NUM_ACTUATOR_OUTPUT_GROUPS 4 /**< for sanity checking */
/**
* @addtogroup topics
* @{
*/
struct actuator_outputs_s { struct actuator_outputs_s {
uint64_t timestamp; /**< output timestamp in us since system boot */ uint64_t timestamp; /**< output timestamp in us since system boot */
float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */ float output[NUM_ACTUATOR_OUTPUTS]; /**< output data, in natural output units */
int noutputs; /**< valid outputs */ int noutputs; /**< valid outputs */
}; };
/**
* @}
*/
/* actuator output sets; this list can be expanded as more drivers emerge */ /* actuator output sets; this list can be expanded as more drivers emerge */
ORB_DECLARE(actuator_outputs_0); ORB_DECLARE(actuator_outputs_0);
ORB_DECLARE(actuator_outputs_1); ORB_DECLARE(actuator_outputs_1);

1
src/modules/uORB/topics/debug_key_value.h

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

11
src/modules/uORB/topics/esc_status.h

@ -51,10 +51,6 @@
#include <stdbool.h> #include <stdbool.h>
#include "../uORB.h" #include "../uORB.h"
/**
* @addtogroup topics @{
*/
/** /**
* The number of ESCs supported. * The number of ESCs supported.
* Current (Q2/2013) we support 8 ESCs, * 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 struct esc_status_s
{ {

10
src/modules/uORB/topics/mission.h

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

10
src/modules/uORB/topics/offboard_control_setpoint.h

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

1
src/modules/uORB/topics/omnidirectional_flow.h

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

9
src/modules/uORB/topics/parameter_update.h

@ -42,11 +42,20 @@
#include <stdint.h> #include <stdint.h>
#include "../uORB.h" #include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
struct parameter_update_s { struct parameter_update_s {
/** time at which the latest parameter was updated */ /** time at which the latest parameter was updated */
uint64_t timestamp; uint64_t timestamp;
}; };
/**
* @}
*/
ORB_DECLARE(parameter_update); ORB_DECLARE(parameter_update);
#endif #endif

10
src/modules/uORB/topics/rc_channels.h

@ -45,11 +45,6 @@
#include <stdint.h> #include <stdint.h>
#include "../uORB.h" #include "../uORB.h"
/**
* @addtogroup topics
* @{
*/
/** /**
* The number of RC channel inputs supported. * The number of RC channel inputs supported.
* Current (Q1/2013) radios support up to 18 channels, * 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. */ RC_CHANNELS_FUNCTION_MAX /**< indicates the number of functions. There can be more functions than RC channels. */
}; };
/**
* @addtogroup topics
* @{
*/
struct rc_channels_s { struct rc_channels_s {
uint64_t timestamp; /**< In microseconds since boot time. */ uint64_t timestamp; /**< In microseconds since boot time. */

10
src/modules/uORB/topics/sensor_combined.h

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

8
src/modules/uORB/topics/subsystem_info.h

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

9
src/modules/uORB/topics/telemetry_status.h

@ -50,6 +50,11 @@ enum TELEMETRY_STATUS_RADIO_TYPE {
TELEMETRY_STATUS_RADIO_TYPE_WIRE TELEMETRY_STATUS_RADIO_TYPE_WIRE
}; };
/**
* @addtogroup topics
* @{
*/
struct telemetry_status_s { struct telemetry_status_s {
uint64_t timestamp; uint64_t timestamp;
enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */ 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 */ uint8_t txbuf; /**< how full the tx buffer is as a percentage */
}; };
/**
* @}
*/
ORB_DECLARE(telemetry_status); ORB_DECLARE(telemetry_status);
#endif /* TOPIC_TELEMETRY_STATUS_H */ #endif /* TOPIC_TELEMETRY_STATUS_H */

1
src/modules/uORB/topics/vehicle_attitude.h

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

9
src/modules/uORB/topics/vehicle_command.h

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

4
src/modules/uORB/topics/vehicle_global_position_set_triplet.h

@ -60,8 +60,8 @@
*/ */
struct vehicle_global_position_set_triplet_s struct vehicle_global_position_set_triplet_s
{ {
bool previous_valid; bool previous_valid; /**< flag indicating previous position is valid */
bool next_valid; bool next_valid; /**< flag indicating next position is valid */
struct vehicle_global_position_setpoint_s previous; struct vehicle_global_position_setpoint_s previous;
struct vehicle_global_position_setpoint_s current; struct vehicle_global_position_setpoint_s current;

8
src/modules/uORB/topics/vehicle_status.h

@ -54,10 +54,6 @@
#include <stdbool.h> #include <stdbool.h>
#include "../uORB.h" #include "../uORB.h"
/**
* @addtogroup topics @{
*/
/* State Machine */ /* State Machine */
typedef enum typedef enum
{ {
@ -137,6 +133,10 @@ enum VEHICLE_BATTERY_WARNING {
VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */ VEHICLE_BATTERY_WARNING_ALERT /**< aleting of low voltage 2. stage */
}; };
/**
* @addtogroup topics
* @{
*/
/** /**
* state machine / state of vehicle. * state machine / state of vehicle.

Loading…
Cancel
Save