From 36679fbb39a57139c03cce85d7d0fbd25383a98a Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sat, 10 Aug 2013 11:22:08 -0400 Subject: Some DSM satellites are fussier about bind pulse timing These values work better --- src/drivers/px4io/px4io.cpp | 3 +-- src/modules/px4iofirmware/dsm.c | 4 ++-- 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index ae56b70b3..5089ce3c7 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1445,9 +1445,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); usleep(500000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_set_rx_out); - usleep(1000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); - usleep(100000); + usleep(50000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); break; diff --git a/src/modules/px4iofirmware/dsm.c b/src/modules/px4iofirmware/dsm.c index ab6e3fec4..b2c0db425 100644 --- a/src/modules/px4iofirmware/dsm.c +++ b/src/modules/px4iofirmware/dsm.c @@ -125,9 +125,9 @@ dsm_bind(uint16_t cmd, int pulses) case dsm_bind_send_pulses: for (int i = 0; i < pulses; i++) { stm32_gpiowrite(usart1RxAsOutp, false); - up_udelay(50); + up_udelay(25); stm32_gpiowrite(usart1RxAsOutp, true); - up_udelay(50); + up_udelay(25); } break; case dsm_bind_reinit_uart: -- cgit v1.2.3 From 1d408b80ad70bd8ea873ce7215c8a92a62461b0f Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 17:19:54 -0400 Subject: Support DSM bind via QGroundControl --- Documentation/dsm_bind.odt | Bin 27043 -> 27123 bytes Documentation/dsm_bind.pdf | Bin 34300 -> 323311 bytes src/drivers/px4io/px4io.cpp | 46 ++++++++++++++++++++---------------- src/modules/sensors/sensor_params.c | 1 + src/modules/sensors/sensors.cpp | 12 ---------- 5 files changed, 26 insertions(+), 33 deletions(-) diff --git a/Documentation/dsm_bind.odt b/Documentation/dsm_bind.odt index 66ea1f1be..587a38883 100644 Binary files a/Documentation/dsm_bind.odt and b/Documentation/dsm_bind.odt differ diff --git a/Documentation/dsm_bind.pdf b/Documentation/dsm_bind.pdf index e62d1ed83..76155569e 100644 Binary files a/Documentation/dsm_bind.pdf and b/Documentation/dsm_bind.pdf differ diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 5089ce3c7..cb61d4aae 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -188,6 +188,12 @@ private: bool _dsm_vcc_ctl; + /** + * System armed + */ + + bool _system_armed; + /** * Trampoline to the worker task */ @@ -355,7 +361,8 @@ PX4IO::PX4IO() : _battery_amp_bias(0), _battery_mamphour_total(0), _battery_last_timestamp(0), - _dsm_vcc_ctl(false) + _dsm_vcc_ctl(false), + _system_armed(false) { /* we need this potentially before it could be set in task_main */ g_dev = this; @@ -672,6 +679,17 @@ PX4IO::task_main() */ if (fds[3].revents & POLLIN) { parameter_update_s pupdate; + int32_t dsm_bind_param; + + // See if bind parameter has been set, and reset it to 0 + param_get(param_find("RC_DSM_BIND"), &dsm_bind_param); + if (dsm_bind_param) { + if (((dsm_bind_param == 1) || (dsm_bind_param == 2)) && !_system_armed) { + ioctl(nullptr, DSM_BIND_START, dsm_bind_param == 1 ? 3 : 7); + } + dsm_bind_param = 0; + param_set(param_find("RC_DSM_BIND"), &dsm_bind_param); + } /* copy to reset the notification */ orb_copy(ORB_ID(parameter_update), _t_param, &pupdate); @@ -737,6 +755,8 @@ PX4IO::io_set_arming_state() uint16_t set = 0; uint16_t clear = 0; + _system_armed = vstatus.flag_system_armed; + if (armed.armed && !armed.lockdown) { set |= PX4IO_P_SETUP_ARMING_FMU_ARMED; } else { @@ -1448,6 +1468,8 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); usleep(50000); io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_send_pulses | (arg << 4)); + usleep(50000); + io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); break; case DSM_BIND_STOP: @@ -1695,30 +1717,12 @@ bind(int argc, char *argv[]) else errx(1, "unknown parameter %s, use dsm2 or dsmx", argv[2]); - /* Open console directly to grab CTRL-C signal */ - int console = open("/dev/console", O_NONBLOCK | O_RDONLY | O_NOCTTY); - if (!console) - errx(1, "failed opening console"); - warnx("This command will only bind DSM if satellite VCC (red wire) is controlled by relay 1."); - warnx("Press CTRL-C or 'c' when done."); g_dev->ioctl(nullptr, DSM_BIND_START, pulses); - for (;;) { - usleep(500000L); - /* Check if user wants to quit */ - char c; - if (read(console, &c, 1) == 1) { - if (c == 0x03 || c == 0x63) { - warnx("Done\n"); - g_dev->ioctl(nullptr, DSM_BIND_STOP, 0); - g_dev->ioctl(nullptr, DSM_BIND_POWER_UP, 0); - close(console); - exit(0); - } - } - } + exit(0); + } void diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 133cda8d6..bd431c9eb 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -156,6 +156,7 @@ PARAM_DEFINE_FLOAT(RC14_DZ, 0.0f); PARAM_DEFINE_INT32(RC_TYPE, 1); /** 1 = FUTABA, 2 = Spektrum, 3 = Graupner HoTT, 4 = Turnigy 9x */ PARAM_DEFINE_INT32(RC_RL1_DSM_VCC, 0); /* Relay 1 controls DSM VCC */ +PARAM_DEFINE_INT32(RC_DSM_BIND, 0); /* 0 = Idle, 1 = Start DSM2 bind, 2 = Start DSMX bind */ /* default is conversion factor for the PX4IO / PX4IOAR board, the factor for PX4FMU standalone is different */ PARAM_DEFINE_FLOAT(BAT_V_SCALING, (3.3f * 52.0f / 5.0f / 4095.0f)); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index f7b41b120..42268b971 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -257,8 +257,6 @@ private: float battery_voltage_scaling; - int rc_rl1_DSM_VCC_control; - } _parameters; /**< local copies of interesting parameters */ struct { @@ -308,8 +306,6 @@ private: param_t battery_voltage_scaling; - param_t rc_rl1_DSM_VCC_control; - } _parameter_handles; /**< handles for interesting parameters */ @@ -544,9 +540,6 @@ Sensors::Sensors() : _parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING"); - /* DSM VCC relay control */ - _parameter_handles.rc_rl1_DSM_VCC_control = param_find("RC_RL1_DSM_VCC"); - /* fetch initial parameter values */ parameters_update(); } @@ -738,11 +731,6 @@ Sensors::parameters_update() warnx("Failed updating voltage scaling param"); } - /* relay 1 DSM VCC control */ - if (param_get(_parameter_handles.rc_rl1_DSM_VCC_control, &(_parameters.rc_rl1_DSM_VCC_control)) != OK) { - warnx("Failed updating relay 1 DSM VCC control"); - } - return OK; } -- cgit v1.2.3 From 35ec651cee89081ceaca63a1641541d8ed0a1467 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 18:07:25 -0400 Subject: Remove unused IOCTLs --- src/drivers/drv_pwm_output.h | 5 +---- src/drivers/px4io/px4io.cpp | 6 ------ 2 files changed, 1 insertion(+), 10 deletions(-) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index 52a667403..ec9d4ca09 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -118,11 +118,8 @@ ORB_DECLARE(output_pwm); /** start DSM bind */ #define DSM_BIND_START _IOC(_PWM_SERVO_BASE, 7) -/** stop DSM bind */ -#define DSM_BIND_STOP _IOC(_PWM_SERVO_BASE, 8) - /** Power up DSM receiver */ -#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 9) +#define DSM_BIND_POWER_UP _IOC(_PWM_SERVO_BASE, 8) /** set a single servo to a specific value */ #define PWM_SERVO_SET(_servo) _IOC(_PWM_SERVO_BASE, 0x20 + _servo) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index cb61d4aae..10ab10ef3 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1472,12 +1472,6 @@ PX4IO::ioctl(file * /*filep*/, int cmd, unsigned long arg) io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); break; - case DSM_BIND_STOP: - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_down); - io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_reinit_uart); - usleep(500000); - break; - case DSM_BIND_POWER_UP: io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_DSM, dsm_bind_power_up); break; -- cgit v1.2.3 From 0b935550439a17856f5218fdcd6be8b864cfd346 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 11 Aug 2013 21:16:55 -0400 Subject: Tell mavlink about bind results --- src/drivers/px4io/px4io.cpp | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 10ab10ef3..960ac06ff 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -577,9 +577,11 @@ void PX4IO::task_main() { hrt_abstime last_poll_time = 0; + int mavlink_fd = ::open(MAVLINK_LOG_DEVICE, 0); log("starting"); + /* * Subscribe to the appropriate PWM output topic based on whether we are the * primary PWM output or not. @@ -679,16 +681,24 @@ PX4IO::task_main() */ if (fds[3].revents & POLLIN) { parameter_update_s pupdate; - int32_t dsm_bind_param; + int32_t dsm_bind_val; + param_t dsm_bind_param; // See if bind parameter has been set, and reset it to 0 - param_get(param_find("RC_DSM_BIND"), &dsm_bind_param); - if (dsm_bind_param) { - if (((dsm_bind_param == 1) || (dsm_bind_param == 2)) && !_system_armed) { - ioctl(nullptr, DSM_BIND_START, dsm_bind_param == 1 ? 3 : 7); + param_get(dsm_bind_param = param_find("RC_DSM_BIND"), &dsm_bind_val); + if (dsm_bind_val) { + if (!_system_armed) { + if ((dsm_bind_val == 1) || (dsm_bind_val == 2)) { + mavlink_log_info(mavlink_fd, "[IO] binding dsm%c rx", dsm_bind_val == 1 ? '2' : 'x'); + ioctl(nullptr, DSM_BIND_START, dsm_bind_val == 1 ? 3 : 7); + } else { + mavlink_log_info(mavlink_fd, "[IO] invalid bind type, bind request rejected"); + } + } else { + mavlink_log_info(mavlink_fd, "[IO] system armed, bind request rejected"); } - dsm_bind_param = 0; - param_set(param_find("RC_DSM_BIND"), &dsm_bind_param); + dsm_bind_val = 0; + param_set(dsm_bind_param, &dsm_bind_val); } /* copy to reset the notification */ -- cgit v1.2.3 From 3a21cacdbbf507f47a45035af7fda04ac787f9b0 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 14 Aug 2013 16:00:35 +0200 Subject: Fix bug where IO was in override mode for copter (workaround was to disconnect and reconnect Rx --- src/modules/px4iofirmware/controls.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 43d96fb06..fbd82a4c6 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -300,6 +300,8 @@ controls_tick() { } else { r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE; } + } else { + r_status_flags &= ~PX4IO_P_STATUS_FLAGS_OVERRIDE; } } -- cgit v1.2.3 From 75e56285901cdb95f0ebbad62d841fbe9d38c1a1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 12:52:07 +0200 Subject: Fixed Doxygen --- Documentation/Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index 4802ef818..fd997baaa 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -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 -- cgit v1.2.3 From a1e0581facd28c8c3f2797e72f810a6674216aa5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 12:55:16 +0200 Subject: Hotfix: More Doxygen fixes --- .gitignore | 4 +++- Documentation/Doxyfile | 4 +--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.gitignore b/.gitignore index 0372b60c8..6ae5baecc 100644 --- a/.gitignore +++ b/.gitignore @@ -24,4 +24,6 @@ Firmware.sublime-workspace Images/*.bin Images/*.px4 mavlink/include/mavlink/v0.9/ -NuttX \ No newline at end of file +/NuttX +/Documentation/doxy.log +/Documentation/html/ \ No newline at end of file diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index fd997baaa..f45fe8b21 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -599,9 +599,7 @@ 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/mathlib/CMSIS # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded -- cgit v1.2.3 From ca877e0bc480e6f28e58a492a64b99a8afe59a21 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 13:00:42 +0200 Subject: Fixed file exclude --- Documentation/Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index f45fe8b21..6283cfc9c 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -599,7 +599,7 @@ 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 = ../src/mathlib/CMSIS +EXCLUDE = ../src/modules/mathlib/CMSIS # The EXCLUDE_SYMLINKS tag can be used select whether or not files or # directories that are symbolic links (a Unix filesystem feature) are excluded -- cgit v1.2.3 From 74d519d9d0560cd0f54ba2667c8c198d1c933fe3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 13:38:59 +0200 Subject: Hotfix: Fixed Doxygen tags for uORB topics --- .gitignore | 3 ++- src/modules/uORB/objects_common.cpp | 4 ++++ src/modules/uORB/topics/actuator_controls.h | 9 +++++++++ src/modules/uORB/topics/actuator_controls_effective.h | 9 +++++++++ src/modules/uORB/topics/actuator_outputs.h | 9 +++++++++ src/modules/uORB/topics/debug_key_value.h | 1 + src/modules/uORB/topics/esc_status.h | 11 ++++++----- src/modules/uORB/topics/mission.h | 10 +++++----- src/modules/uORB/topics/offboard_control_setpoint.h | 10 +++++----- src/modules/uORB/topics/omnidirectional_flow.h | 1 + src/modules/uORB/topics/parameter_update.h | 9 +++++++++ src/modules/uORB/topics/rc_channels.h | 10 +++++----- src/modules/uORB/topics/sensor_combined.h | 10 +++++----- src/modules/uORB/topics/subsystem_info.h | 8 ++++---- src/modules/uORB/topics/telemetry_status.h | 9 +++++++++ src/modules/uORB/topics/vehicle_attitude.h | 1 + src/modules/uORB/topics/vehicle_command.h | 9 ++++----- src/modules/uORB/topics/vehicle_global_position_set_triplet.h | 4 ++-- src/modules/uORB/topics/vehicle_status.h | 8 ++++---- 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 #include 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 @@ -51,10 +51,6 @@ #include #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 #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. * 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 @@ -43,11 +43,6 @@ #include #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; 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 #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 @@ -45,11 +45,6 @@ #include #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. */ 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,17 +46,17 @@ #include #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. * 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 #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 */ 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 @@ -45,11 +45,6 @@ #include #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 { 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 #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. -- cgit v1.2.3 From b83d07e94a0db879ff59a45f69450152ae330150 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 15 Aug 2013 13:47:36 +0200 Subject: Hotfix: Excluding codegen code --- Documentation/Doxyfile | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index 6283cfc9c..65274d4a4 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -599,7 +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 = ../src/modules/mathlib/CMSIS +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 -- cgit v1.2.3 From 6113be111e84a57715f3f3bfe81077bf1b267e52 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 16 Aug 2013 14:25:21 +0200 Subject: Hotfix: Do not create bug/test lists, adding noise --- Documentation/Doxyfile | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Documentation/Doxyfile b/Documentation/Doxyfile index 65274d4a4..241702811 100644 --- a/Documentation/Doxyfile +++ b/Documentation/Doxyfile @@ -429,19 +429,19 @@ SORT_BY_SCOPE_NAME = NO # disable (NO) the todo list. This list is created by putting \todo # commands in the documentation. -GENERATE_TODOLIST = YES +GENERATE_TODOLIST = NO # The GENERATE_TESTLIST tag can be used to enable (YES) or # disable (NO) the test list. This list is created by putting \test # commands in the documentation. -GENERATE_TESTLIST = YES +GENERATE_TESTLIST = NO # The GENERATE_BUGLIST tag can be used to enable (YES) or # disable (NO) the bug list. This list is created by putting \bug # commands in the documentation. -GENERATE_BUGLIST = YES +GENERATE_BUGLIST = NO # The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or # disable (NO) the deprecated list. This list is created by putting -- cgit v1.2.3