From da3a92a023a53669eed507342d133fa8d584d7ab Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Wed, 6 Jul 2011 09:35:32 +0200 Subject: [PATCH 001/112] implementation of gls (gps landing system) and border line --- .../fixedwing/navigation_extra.makefile | 2 + .../subsystems/navigation/border_line.c | 132 +++++++++++++ .../subsystems/navigation/border_line.h | 35 ++++ sw/airborne/subsystems/navigation/gls.c | 174 ++++++++++++++++++ sw/airborne/subsystems/navigation/gls.h | 35 ++++ 5 files changed, 378 insertions(+) create mode 100644 sw/airborne/subsystems/navigation/border_line.c create mode 100644 sw/airborne/subsystems/navigation/border_line.h create mode 100644 sw/airborne/subsystems/navigation/gls.c create mode 100644 sw/airborne/subsystems/navigation/gls.h diff --git a/conf/autopilot/subsystems/fixedwing/navigation_extra.makefile b/conf/autopilot/subsystems/fixedwing/navigation_extra.makefile index 933150953b..c9d42eda7b 100644 --- a/conf/autopilot/subsystems/fixedwing/navigation_extra.makefile +++ b/conf/autopilot/subsystems/fixedwing/navigation_extra.makefile @@ -17,4 +17,6 @@ $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/OSAMNav.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/snav.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/spiral.c $(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/poly_survey_adv.c +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/gls.c +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/navigation/border_line.c diff --git a/sw/airborne/subsystems/navigation/border_line.c b/sw/airborne/subsystems/navigation/border_line.c new file mode 100644 index 0000000000..30a5bb31a5 --- /dev/null +++ b/sw/airborne/subsystems/navigation/border_line.c @@ -0,0 +1,132 @@ +/* + * $Id$ + * + * Copyright (C) 2012 Tobias Muench + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/* +modified nav_linie by Anton Kochevar, ENAC +navigate along a border line (line 1-2) with turns in the same direction + +*/ + +#include "subsystems/navigation/border_line.h" +#include "generated/airframe.h" +#include "subsystems/nav.h" + + +enum border_line_status { LR12, LQC21, LTC2, LQC22, LR21, LQC12, LTC1, LQC11 }; +static enum border_line_status border_line_status; + +bool_t border_line_init( void ) { + border_line_status = LR12; + return FALSE; +} + +bool_t border_line(uint8_t l1, uint8_t l2, float radius) { + radius = fabs(radius); + float alt = waypoints[l1].a; + waypoints[l2].a = alt; + + float l2_l1_x = WaypointX(l1) - WaypointX(l2); + float l2_l1_y = WaypointY(l1) - WaypointY(l2); + float d = sqrt(l2_l1_x*l2_l1_x+l2_l1_y*l2_l1_y); + + float u_x = l2_l1_x / d; + float u_y = l2_l1_y / d; + + float angle = atan2((WaypointY(l1)-WaypointY(l2)),(WaypointX(l2)-WaypointX(l1))); + + struct point l2_c1 = { WaypointX(l1) - sin(angle)*radius, + WaypointY(l1) - cos(angle)*radius, + alt }; + struct point l2_c2 = { l2_c1.x + 2*radius*cos(angle) , + l2_c1.y - 2*radius*sin(angle), + alt }; + + + + struct point l1_c2 = { WaypointX(l2) - sin(angle)*radius, + WaypointY(l2) - cos(angle)*radius, + alt }; + struct point l1_c3 = { l1_c2.x - 2*radius*cos(angle) , + l1_c2.y + 2*radius*sin(angle), + alt }; + + float qdr_out_2_1 = M_PI/3. - atan2(u_y, u_x); + float qdr_out_2_2 = -M_PI/3. - atan2(u_y, u_x); + float qdr_out_2_3 = M_PI - atan2(u_y, u_x); + + + NavVerticalAutoThrottleMode(0); + NavVerticalAltitudeMode(WaypointAlt(l1), 0.); + + switch (border_line_status) { + case LR12: + NavSegment(l2, l1); + if (NavApproachingFrom(l1, l2, CARROT)) { + border_line_status = LQC21; + nav_init_stage(); + } + break; + case LQC21: + nav_circle_XY(l2_c1.x, l2_c1.y, -radius); + if (NavQdrCloseTo(DegOfRad(qdr_out_2_2)-10)) { + border_line_status = LTC2; + nav_init_stage(); + } + break; + case LTC2: + nav_circle_XY(l2_c2.x, l2_c2.y, radius); + if (NavQdrCloseTo(DegOfRad(qdr_out_2_3)-10)) { + border_line_status = LR21; + nav_init_stage(); + } + break; + + case LR21: + NavSegment(l1, l2); + if (NavApproachingFrom(l2, l1, CARROT)) { + border_line_status = LTC1; + nav_init_stage(); + } + break; + + case LTC1: + nav_circle_XY(l1_c2.x, l1_c2.y, radius); + if (NavQdrCloseTo(DegOfRad(qdr_out_2_1) + 10)) { + border_line_status = LQC11; + nav_init_stage(); + } + break; + case LQC11: + nav_circle_XY(l1_c3.x, l1_c3.y, -radius); + if (NavQdrCloseTo(DegOfRad(qdr_out_2_3 + M_PI + 10))) { + border_line_status = LR12; + nav_init_stage(); + } + break; + + default: /* Should not occur !!! End the pattern */ + return FALSE; + } + return TRUE; /* This pattern never ends */ +} diff --git a/sw/airborne/subsystems/navigation/border_line.h b/sw/airborne/subsystems/navigation/border_line.h new file mode 100644 index 0000000000..e3c51c9b29 --- /dev/null +++ b/sw/airborne/subsystems/navigation/border_line.h @@ -0,0 +1,35 @@ +/* + * $Id$ + * + * Copyright (C) 2012, Tobias Muench + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#ifndef BORDER_LINE_H +#define BORDER_LINE_H + +#include "std.h" + +extern bool_t border_line_init( void ); +extern bool_t border_line(uint8_t wp1, uint8_t wp2, float radius); + +#endif + +/* BORDER_LINE_H */ diff --git a/sw/airborne/subsystems/navigation/gls.c b/sw/airborne/subsystems/navigation/gls.c new file mode 100644 index 0000000000..a89da428f8 --- /dev/null +++ b/sw/airborne/subsystems/navigation/gls.c @@ -0,0 +1,174 @@ +/* + * + * Copyright (C) 2012, Tobias Münch + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/* +gps landing system +-automatic calculation of top of decent for const app angle +-smooth intercept posible +-landing direction is set by app fix + +in airframe.xml +it is possible to define + +1. target_speed +2. app_angle +3. app_intercept_af_tod + +1 - only efective with useairspeed flag +2 - defauld is a approach angle of 5 degree which should be fine for most planes +3 - distance between approach fix and top of decent +*/ + + + +#include "generated/airframe.h" +#include "estimator.h" +#include "subsystems/navigation/gls.h" +#include "subsystems/nav.h" +#include "generated/flight_plan.h" + + + +float target_speed; +float app_angle; +float app_intercept_af_tod; + +bool_t init = TRUE; + +#ifndef APP_TARGET_SPEED +#define APP_TARGET_SPEED V_CTL_AUTO_AIRSPEED_SETPOINT; +#endif + +#ifndef APP_ANGLE +#define APP_ANGLE 5; +#endif + +#ifndef APP_INTERCEPT_AF_TOD +#define APP_INTERCEPT_AF_TOD 100 +#endif + + +static inline bool_t gls_compute_TOD(uint8_t _af, uint8_t _tod, uint8_t _td, float app_angle) { + + if ((WaypointX(_af)==WaypointX(_td))&&(WaypointY(_af)==WaypointY(_td))){ + WaypointX(_af)=WaypointX(_td)-1; + } + + float td_af_x = WaypointX(_af) - WaypointX(_td); + float td_af_y = WaypointY(_af) - WaypointY(_td); + float td_af = sqrt( td_af_x*td_af_x + td_af_y*td_af_y); + float td_tod = (WaypointAlt(_af) - WaypointAlt(_td)) / (tan(RadOfDeg(app_angle))); + + WaypointX(_tod) = WaypointX(_td) + td_af_x / td_af * td_tod; + WaypointY(_tod) = WaypointY(_td) + td_af_y / td_af * td_tod; + WaypointAlt(_tod) = WaypointAlt(_af); + + if (td_tod > td_af) { + WaypointX(_af) = WaypointX(_tod) + td_af_x / td_af * app_intercept_af_tod; + WaypointY(_af) = WaypointY(_tod) + td_af_y / td_af * app_intercept_af_tod; + } + return FALSE; +} // end of gls_copute_TOD + + +//############################################################################################### + +bool_t gls_init(uint8_t _af, uint8_t _tod, uint8_t _td) { + + init = TRUE; + + #ifdef USE_AIRSPEED +// float wind_additional = sqrt(wind_east*wind_east + wind_north*wind_north); // should be gusts only! +// Bound(wind_additional, 0, 0.5); +// target_speed = FL_ENVE_V_S * 1.3 + wind_additional; FIXME + target_speed = APP_TARGET_SPEED; // ok for now! + #endif + + app_angle = APP_ANGLE; + app_intercept_af_tod = APP_INTERCEPT_AF_TOD; + Bound(app_intercept_af_tod,0,200); + + + gls_compute_TOD(_af, _tod, _td, app_angle); // calculate Top Of Decent + + return FALSE; +} // end of gls_init() + + +//############################################################################################### + + +bool_t gls(uint8_t _af, uint8_t _tod, uint8_t _td) { + + + if (init){ + + #ifdef USE_AIRSPEED + v_ctl_auto_airspeed_setpoint = target_speed; // set target speed for approach + #endif + init = FALSE; + + } + + + float final_x = WaypointX(_td) - WaypointX(_tod); + float final_y = WaypointY(_td) - WaypointY(_tod); + float final2 = Max(final_x * final_x + final_y * final_y, 1.); + + float nav_final_progress = ((estimator_x - WaypointX(_tod)) * final_x + (estimator_y - WaypointY(_tod)) * final_y) / final2; + Bound(nav_final_progress,-1,1); + float nav_final_length = sqrt(final2); + + float pre_climb = -(WaypointAlt(_tod) - WaypointAlt(_td)) / (nav_final_length / estimator_hspeed_mod); + Bound(pre_climb, -5, 0.); + + float start_alt = WaypointAlt(_tod); + float diff_alt = WaypointAlt(_td) - start_alt; + float alt = start_alt + nav_final_progress * diff_alt; + Bound(alt, WaypointAlt(_td), start_alt +(pre_climb/(v_ctl_altitude_pgain))) // to prevent climbing before intercept + + + + + if(nav_final_progress < -0.5) { // for smooth intercept + + NavVerticalAltitudeMode(WaypointAlt(_tod), 0); // vertical mode (fly straigt and intercept glideslope) + + NavVerticalAutoThrottleMode(0); // throttle mode + + NavSegment(_af, _td); // horizontal mode (stay on localiser) + } + + else { // + + NavVerticalAltitudeMode(alt, pre_climb); // vertical mode (folow glideslope) + + NavVerticalAutoThrottleMode(0); // throttle mode + + NavSegment(_af, _td); // horizontal mode (stay on localiser) + } + + +return TRUE; + +} // end of gls() diff --git a/sw/airborne/subsystems/navigation/gls.h b/sw/airborne/subsystems/navigation/gls.h new file mode 100644 index 0000000000..b26d1d0efe --- /dev/null +++ b/sw/airborne/subsystems/navigation/gls.h @@ -0,0 +1,35 @@ +/* + * + * Copyright (C) 2012, Tobias Muench + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#ifndef NAV_GLS_H +#define NAV_GLS_H + +#include "std.h" +#include "paparazzi.h" + + + +extern bool_t gls_init(uint8_t _af, uint8_t _tod, uint8_t _td); +extern bool_t gls(uint8_t _af, uint8_t _tod, uint8_t _td); + +#endif From ea478bc9636eeca7bfa7bf9f97a6ffbd6c23847e Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Wed, 6 Jul 2011 10:17:36 +0200 Subject: [PATCH 002/112] changed app_angle to global var --- sw/airborne/subsystems/navigation/gls.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/subsystems/navigation/gls.c b/sw/airborne/subsystems/navigation/gls.c index a89da428f8..fe8ed40613 100644 --- a/sw/airborne/subsystems/navigation/gls.c +++ b/sw/airborne/subsystems/navigation/gls.c @@ -68,7 +68,7 @@ bool_t init = TRUE; #endif -static inline bool_t gls_compute_TOD(uint8_t _af, uint8_t _tod, uint8_t _td, float app_angle) { +static inline bool_t gls_compute_TOD(uint8_t _af, uint8_t _tod, uint8_t _td) { if ((WaypointX(_af)==WaypointX(_td))&&(WaypointY(_af)==WaypointY(_td))){ WaypointX(_af)=WaypointX(_td)-1; @@ -109,7 +109,7 @@ bool_t gls_init(uint8_t _af, uint8_t _tod, uint8_t _td) { Bound(app_intercept_af_tod,0,200); - gls_compute_TOD(_af, _tod, _td, app_angle); // calculate Top Of Decent + gls_compute_TOD(_af, _tod, _td); // calculate Top Of Decent return FALSE; } // end of gls_init() From da8b12d0974cd4733c4b1a76f84c199065fbaa98 Mon Sep 17 00:00:00 2001 From: Tobias Muench Date: Wed, 6 Jul 2011 10:49:26 +0200 Subject: [PATCH 003/112] doxygen --- .../subsystems/navigation/border_line.c | 11 +++++-- sw/airborne/subsystems/navigation/gls.c | 33 ++++++++++--------- 2 files changed, 25 insertions(+), 19 deletions(-) diff --git a/sw/airborne/subsystems/navigation/border_line.c b/sw/airborne/subsystems/navigation/border_line.c index 30a5bb31a5..39d72d3173 100644 --- a/sw/airborne/subsystems/navigation/border_line.c +++ b/sw/airborne/subsystems/navigation/border_line.c @@ -22,10 +22,15 @@ * */ -/* -modified nav_linie by Anton Kochevar, ENAC -navigate along a border line (line 1-2) with turns in the same direction +//modified nav_linie by Anton Kochevar, ENAC + +/** + * \brief navigate along a border line (line 1-2) with turns in the same direction + * + * you can use this function to navigate along a border if it is essetial not to cross it + * navigation is along line p1, p2 with turns in the same direction to make sure you dont cross the line + * take care youre navigation radius is not to smal in strong wind conditions! */ #include "subsystems/navigation/border_line.h" diff --git a/sw/airborne/subsystems/navigation/gls.c b/sw/airborne/subsystems/navigation/gls.c index fe8ed40613..f79d641b40 100644 --- a/sw/airborne/subsystems/navigation/gls.c +++ b/sw/airborne/subsystems/navigation/gls.c @@ -21,22 +21,23 @@ * */ -/* -gps landing system --automatic calculation of top of decent for const app angle --smooth intercept posible --landing direction is set by app fix - -in airframe.xml -it is possible to define - -1. target_speed -2. app_angle -3. app_intercept_af_tod - -1 - only efective with useairspeed flag -2 - defauld is a approach angle of 5 degree which should be fine for most planes -3 - distance between approach fix and top of decent +/** + * \brief gps landing system + * gps landing system + * -automatic calculation of top of decent for const app angle + * -smooth intercept posible + * -landing direction is set by app fix / also possible in flight!!! + * + * in airframe.xml + * it is possible to define + * + * 1. target_speed + * 2. app_angle + * 3. app_intercept_af_tod + * + * 1 - only efective with useairspeed flag + * 2 - defauld is a approach angle of 5 degree which should be fine for most planes + * 3 - distance between approach fix and top of decent */ From 8b2892c0052ac9b4da597e400e490fa117c44577 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 2 Nov 2011 15:59:30 +0100 Subject: [PATCH 004/112] Trim Fixedwing Inflight: Stop abusing ins_neutral/ir_neutral --- conf/settings/tuning.xml | 5 +++++ conf/settings/tuning_ins.xml | 5 +++++ sw/airborne/commands.c | 11 +++++++++++ sw/airborne/commands.h | 2 ++ sw/airborne/firmwares/fixedwing/main_fbw.c | 13 ++++++++++++- 5 files changed, 35 insertions(+), 1 deletion(-) diff --git a/conf/settings/tuning.xml b/conf/settings/tuning.xml index 8e9538720e..c430c97e34 100644 --- a/conf/settings/tuning.xml +++ b/conf/settings/tuning.xml @@ -31,6 +31,11 @@ + + + + + diff --git a/conf/settings/tuning_ins.xml b/conf/settings/tuning_ins.xml index 1f092a4a56..0a5aea0529 100644 --- a/conf/settings/tuning_ins.xml +++ b/conf/settings/tuning_ins.xml @@ -31,6 +31,11 @@ + + + + + diff --git a/sw/airborne/commands.c b/sw/airborne/commands.c index c73b50081f..3dd61cfdd3 100644 --- a/sw/airborne/commands.c +++ b/sw/airborne/commands.c @@ -28,5 +28,16 @@ #include "commands.h" +#ifndef COMMAND_ROLL_TRIM +#define COMMAND_ROLL_TRIM 0 +#endif + +#ifndef COMMAND_PITCH_TRIM +#define COMMAND_PITCH_TRIM 0 +#endif + +pprz_t command_roll_trim = COMMAND_ROLL_TRIM; +pprz_t command_pitch_trim = COMMAND_PITCH_TRIM; + pprz_t commands[COMMANDS_NB]; const pprz_t commands_failsafe[COMMANDS_NB] = COMMANDS_FAILSAFE; diff --git a/sw/airborne/commands.h b/sw/airborne/commands.h index a824de01c9..4716959233 100644 --- a/sw/airborne/commands.h +++ b/sw/airborne/commands.h @@ -32,6 +32,8 @@ #include "paparazzi.h" #include "generated/airframe.h" +extern pprz_t command_roll_trim; +extern pprz_t command_pitch_trim; extern pprz_t commands[COMMANDS_NB]; extern const pprz_t commands_failsafe[COMMANDS_NB]; diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 40dcf65a58..7b70a8f900 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -150,7 +150,18 @@ void event_task_fbw( void) { #ifdef ACTUATORS if (fbw_new_actuators > 0) { - SetActuatorsFromCommands(commands); + pprz_t trimmed_commands[COMMANDS_NB]; + int i; + for(i = 0; i < COMMANDS_NB; i++) trimmed_commands[i] = commands[i]; + + #ifdef COMMAND_ROLL + trimmed_commands[COMMAND_ROLL] += command_roll_trim; + #endif + #ifdef COMMAND_PITCH + trimmed_commands[COMMAND_PITCH] += command_pitch_trim; + #endif + + SetActuatorsFromCommands(trimmed_commands); fbw_new_actuators = 0; } #endif From ed6d8b839e170f473ae05c0a8fe4cb5b9852e620 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 18 Nov 2011 11:58:50 +0100 Subject: [PATCH 005/112] distclean target update: remove all non-repository files. make all example airframes --- Makefile | 14 +++++++++++--- 1 file changed, 11 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index 6044b42f05..618351409d 100644 --- a/Makefile +++ b/Makefile @@ -247,9 +247,14 @@ cleanspaces: find ./conf -name '*.xml' -exec sed -i {} -e 's/[ \t]*$$//' ';' distclean : dist_clean -dist_clean : clean - rm -r conf/srtm_data - rm -r conf/maps_data conf/maps.xml +dist_clean : + @echo "Warning: This remove all non-repository files. This means you will loose your aircraft list, your maps, your logfiles, ... if you want this, then run: make dist_clean_irirreversible" + +dist_clean_irreversible: clean + rm -rf conf/srtm_data + rm -rf conf/maps_data conf/maps.xml + rm -rf conf/conf.xml conf/controlpanel.xml + rm -rf var ab_clean: find sw/airborne -name '*~' -exec rm -f {} \; @@ -260,6 +265,9 @@ test_all_example_airframes: $(MAKE) AIRCRAFT=Tiny_IMU clean_ac ap $(MAKE) AIRCRAFT=EasyStar_ETS clean_ac ap sim +test_all_example_airframes2: all + for ap in `grep name conf/conf.xml.example | sed -e 's/.*name=\"//' | sed -e 's/"//'`; do echo "Making $$ap"; make -C ./ AIRCRAFT=$$ap clean_ac ap.compile; done + commands: paparazzi sw/simulator/launchsitl paparazzi: From 3403cb8478e09bda77f68ce3a3bda1ff669c87c9 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 18 Nov 2011 12:33:36 +0100 Subject: [PATCH 006/112] Cleanup the cleaning progress: less cleaning errors --- Makefile | 10 +++++----- data/maps/Makefile | 3 +++ data/srtm/Makefile | 4 ++++ sw/ground_segment/misc/Makefile | 2 +- sw/ground_segment/tmtc/GSM/Makefile | 2 +- sw/in_progress/satcom/Makefile | 2 +- sw/simulator/old_booz/tests/Makefile | 3 +++ 7 files changed, 18 insertions(+), 8 deletions(-) diff --git a/Makefile b/Makefile index 618351409d..c7d1973cf3 100644 --- a/Makefile +++ b/Makefile @@ -233,11 +233,11 @@ fast_deb: $(MAKE) deb OCAMLC=ocamlc.opt DEBFLAGS=-b clean: - rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-arm7 debian/paparazzi-avr debian/paparazzi-base debian/paparazzi-bin debian/paparazzi-dev - rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(DL_PROTOCOL_H) - find . -mindepth 2 -name Makefile -exec sh -c '$(MAKE) -C `dirname {}` $@' \; - find . -name '*~' -exec rm -f {} \; - rm -f paparazzi sw/simulator/launchsitl + $(Q)rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-arm7 debian/paparazzi-avr debian/paparazzi-base debian/paparazzi-bin debian/paparazzi-dev + $(Q)rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(DL_PROTOCOL_H) + $(Q)find . -mindepth 2 -name Makefile -exec sh -c 'echo "Cleaning {}"; $(MAKE) -C `dirname {}` $@' \; + $(Q)find . -name '*~' -exec rm -f {} \; + $(Q)rm -f paparazzi sw/simulator/launchsitl cleanspaces: find ./sw/airborne -name '*.[ch]' -exec sed -i {} -e 's/[ \t]*$$//' \; diff --git a/data/maps/Makefile b/data/maps/Makefile index 9a676c715c..d17507da42 100644 --- a/data/maps/Makefile +++ b/data/maps/Makefile @@ -3,6 +3,9 @@ Q=@ all: $(DATADIR)/maps.google.com $(PAPARAZZI_HOME)/conf/maps.xml +clean: + + $(DATADIR): mkdir $(DATADIR) diff --git a/data/srtm/Makefile b/data/srtm/Makefile index 0e24687031..80ac333eee 100644 --- a/data/srtm/Makefile +++ b/data/srtm/Makefile @@ -3,6 +3,9 @@ Q=@ SRTMData: $(DATADIR)/Africa $(DATADIR)/Australia $(DATADIR)/Eurasia $(DATADIR)/Islands $(DATADIR)/North_America $(DATADIR)/South_America +clean: + + $(DATADIR): mkdir $(DATADIR) @@ -29,3 +32,4 @@ $(DATADIR)/South_America: $(DATADIR) %.hgt.zip: SRTMData $(Q)wget -c -nv -N http://dds.cr.usgs.gov/srtm/version2_1/SRTM3/$(shell grep -l $(@F) $(DATADIR)/* | sed -e s#$(DATADIR)/##)/$(@F) + diff --git a/sw/ground_segment/misc/Makefile b/sw/ground_segment/misc/Makefile index 9e15b25a0f..d7cf0118fb 100644 --- a/sw/ground_segment/misc/Makefile +++ b/sw/ground_segment/misc/Makefile @@ -10,7 +10,7 @@ endif all: davis2ivy kestrel2ivy clean: - rm *.o davis2ivy kestrel2ivy + rm -f *.o davis2ivy kestrel2ivy davis2ivy: davis2ivy.o g++ -o davis2ivy davis2ivy.o $(LIBRARYS) -livy diff --git a/sw/ground_segment/tmtc/GSM/Makefile b/sw/ground_segment/tmtc/GSM/Makefile index e731282280..697b8399d9 100644 --- a/sw/ground_segment/tmtc/GSM/Makefile +++ b/sw/ground_segment/tmtc/GSM/Makefile @@ -4,4 +4,4 @@ SMS_GS: SMS_Ground_UDtest_final.c gcc -g -O2 -Wall `pkg-config --cflags glib-2.0 gtk+-2.0` -L/usr/lib -lglibivy -o SMS_GS SMS_Ground_UDtest_final.c `pkg-config --libs glib-2.0 gtk+-2.0` -lglibivy clean: - rm SMS_GS + rm -f SMS_GS diff --git a/sw/in_progress/satcom/Makefile b/sw/in_progress/satcom/Makefile index 339fb51001..0c780f676d 100644 --- a/sw/in_progress/satcom/Makefile +++ b/sw/in_progress/satcom/Makefile @@ -10,4 +10,4 @@ tcp2ivy_generic: tcp2ivy_generic.c gcc -g -O2 -Wall `pkg-config glib-2.0 --cflags` -I../../../var/${AIRCRAFT} -o $@ $^ `pkg-config glib-2.0 --libs` -lglibivy -lm clean: - rm email2udp udp2tcp tcp2ivy + rm -f email2udp udp2tcp tcp2ivy diff --git a/sw/simulator/old_booz/tests/Makefile b/sw/simulator/old_booz/tests/Makefile index 35c5ec7f91..13d0e57905 100644 --- a/sw/simulator/old_booz/tests/Makefile +++ b/sw/simulator/old_booz/tests/Makefile @@ -68,3 +68,6 @@ TEST_SENSORS_SRCS = test_sensors.c \ test_sensors : $(TEST_SENSORS_SRCS) gcc $(CFLAGS) -o $@ $^ $(LDFLAGS) + +clean: + From 3d2bbc2d3a6099ea27afb7ef5087b0cb57b6ba73 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 18 Nov 2011 12:44:16 +0100 Subject: [PATCH 007/112] cleanup --- Makefile | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Makefile b/Makefile index c7d1973cf3..2f8b5b382c 100644 --- a/Makefile +++ b/Makefile @@ -233,7 +233,7 @@ fast_deb: $(MAKE) deb OCAMLC=ocamlc.opt DEBFLAGS=-b clean: - $(Q)rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-arm7 debian/paparazzi-avr debian/paparazzi-base debian/paparazzi-bin debian/paparazzi-dev + $(Q)rm -fr dox build-stamp configure-stamp conf/%gconf.xml debian/files debian/paparazzi-base debian/paparazzi-bin $(Q)rm -f $(MESSAGES_H) $(MESSAGES2_H) $(UBX_PROTOCOL_H) $(MTK_PROTOCOL_H) $(DL_PROTOCOL_H) $(Q)find . -mindepth 2 -name Makefile -exec sh -c 'echo "Cleaning {}"; $(MAKE) -C `dirname {}` $@' \; $(Q)find . -name '*~' -exec rm -f {} \; @@ -247,8 +247,8 @@ cleanspaces: find ./conf -name '*.xml' -exec sed -i {} -e 's/[ \t]*$$//' ';' distclean : dist_clean -dist_clean : - @echo "Warning: This remove all non-repository files. This means you will loose your aircraft list, your maps, your logfiles, ... if you want this, then run: make dist_clean_irirreversible" +dist_clean : + @echo "Warning: This removes all non-repository files. This means you will loose your aircraft list, your maps, your logfiles, ... if you want this, then run: make dist_clean_irreversible" dist_clean_irreversible: clean rm -rf conf/srtm_data From 1587f9db8faba35fd7ce578d897455ead5d733f8 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 18 Nov 2011 14:57:26 +0100 Subject: [PATCH 008/112] Makefile warning cleaning continued --- Makefile | 2 +- data/maps/Makefile | 3 ++- sw/in_progress/videolizer/wis-go7007-linux/kernel/Makefile | 3 +++ sw/lib/ocaml/ivy/Makefile | 2 ++ sw/lib/ocaml/ivy/examples/Makefile | 2 ++ sw/simulator/scilab/q3d/fonts/Makefile | 4 ++++ 6 files changed, 14 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 2f8b5b382c..b4c88c3627 100644 --- a/Makefile +++ b/Makefile @@ -265,7 +265,7 @@ test_all_example_airframes: $(MAKE) AIRCRAFT=Tiny_IMU clean_ac ap $(MAKE) AIRCRAFT=EasyStar_ETS clean_ac ap sim -test_all_example_airframes2: all +test_all_example_airframes2: for ap in `grep name conf/conf.xml.example | sed -e 's/.*name=\"//' | sed -e 's/"//'`; do echo "Making $$ap"; make -C ./ AIRCRAFT=$$ap clean_ac ap.compile; done commands: paparazzi sw/simulator/launchsitl diff --git a/data/maps/Makefile b/data/maps/Makefile index d17507da42..995c5bb98b 100644 --- a/data/maps/Makefile +++ b/data/maps/Makefile @@ -10,7 +10,8 @@ $(DATADIR): mkdir $(DATADIR) $(DATADIR)/maps.google.com: $(DATADIR) FORCE - wget -O $(@) http://maps.google.com/ + @echo "DOWNLOAD: google maps version code"; + $(Q)wget -q -O $(@) http://maps.google.com/ $(PAPARAZZI_HOME)/conf/maps.xml: $(DATADIR)/maps.google.com $(Q)echo "" > $(@) diff --git a/sw/in_progress/videolizer/wis-go7007-linux/kernel/Makefile b/sw/in_progress/videolizer/wis-go7007-linux/kernel/Makefile index 6719a89748..a84508cb59 100644 --- a/sw/in_progress/videolizer/wis-go7007-linux/kernel/Makefile +++ b/sw/in_progress/videolizer/wis-go7007-linux/kernel/Makefile @@ -5,6 +5,9 @@ obj-m += go7007.o go7007-usb.o snd-go7007.o wis-saa7115.o wis-tw9903.o \ wis-tw2804.o go7007-objs := go7007-v4l2.o go7007-driver.o go7007-i2c.o go7007-fw.o +clean: + rm -f $(obj-m) + ifneq ($(SAA7134_BUILD),) obj-m += saa7134-go7007.o endif diff --git a/sw/lib/ocaml/ivy/Makefile b/sw/lib/ocaml/ivy/Makefile index abacbdf640..24613416c7 100644 --- a/sw/lib/ocaml/ivy/Makefile +++ b/sw/lib/ocaml/ivy/Makefile @@ -122,4 +122,6 @@ clean: .depend: $(OCAMLDEP) $(INCLUDES) *.mli *.ml > .depend +ifneq ($(MAKECMDGOALS),clean) include .depend +endif diff --git a/sw/lib/ocaml/ivy/examples/Makefile b/sw/lib/ocaml/ivy/examples/Makefile index 2d4c27fc44..53fa3ae7c4 100644 --- a/sw/lib/ocaml/ivy/examples/Makefile +++ b/sw/lib/ocaml/ivy/examples/Makefile @@ -26,4 +26,6 @@ clean: .depend: $(OCAMLDEP) $(INCLUDES) *.mli *.ml > .depend +ifneq ($(MAKECMDGOALS),clean) include .depend +endif diff --git a/sw/simulator/scilab/q3d/fonts/Makefile b/sw/simulator/scilab/q3d/fonts/Makefile index 9ec1ddeda5..f99fbddd80 100644 --- a/sw/simulator/scilab/q3d/fonts/Makefile +++ b/sw/simulator/scilab/q3d/fonts/Makefile @@ -4,3 +4,7 @@ GLIB_LDFLAGS = `pkg-config glib-2.0 --libs` -lglibivy -lpcre ttx2scilab: ttx2scilab.c $(CC) -Wall $(GLIB_CFLAGS) -o $@ $< $(GLIB_LDFLAGS) + +clean: + rm -f ttx2scilab + From f8f68db40c441e7c9ccc08772d8144a7df8a25d5 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Fri, 18 Nov 2011 15:24:04 +0100 Subject: [PATCH 009/112] removed even more warnings --- sw/airborne/firmwares/rotorcraft/autopilot.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/firmwares/rotorcraft/autopilot.c b/sw/airborne/firmwares/rotorcraft/autopilot.c index 6cc818a313..125937e453 100644 --- a/sw/airborne/firmwares/rotorcraft/autopilot.c +++ b/sw/airborne/firmwares/rotorcraft/autopilot.c @@ -287,6 +287,8 @@ static inline void autopilot_check_motors_on( void ) { if (!(THROTTLE_STICK_DOWN() && YAW_STICK_PUSHED())) // wait until stick released autopilot_check_motor_status = STATUS_MOTORS_OFF; break; + default: + break; }; } From fd2a6ffc55b21a58fc15911102c434eb7f72af5f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 19 Nov 2011 13:56:02 +0100 Subject: [PATCH 010/112] fixes generation of Makefile.ac, previously failed if processor attribute was set for target. fixes issue #90 --- sw/tools/gen_aircraft.ml | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/sw/tools/gen_aircraft.ml b/sw/tools/gen_aircraft.ml index 72b25931d4..7e0f1efaba 100644 --- a/sw/tools/gen_aircraft.ml +++ b/sw/tools/gen_aircraft.ml @@ -232,7 +232,12 @@ let parse_firmware = fun makefile_ac firmware -> (* print makefile for this target *) fprintf makefile_ac "\n###########\n# -target: '%s'\n" (Xml.attrib target "name"); fprintf makefile_ac "ifeq ($(TARGET), %s)\n" (Xml.attrib target "name"); - try fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor") with _ -> (); + let has_processor = + try + not (String.compare (Xml.attrib target "processor") "" = 0) + with _ -> false in + if has_processor then + fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor"); List.iter (print_firmware_configure makefile_ac) config; List.iter (print_firmware_configure makefile_ac) t_config; List.iter (print_firmware_define makefile_ac) defines; From fc052616bbea932352a6c2c44e8a1a2cc6afae6c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 20 Nov 2011 12:01:48 +0100 Subject: [PATCH 011/112] fix for finding libopencm3 correctly, also define RM in case of picking up the compiler from the path --- conf/Makefile.stm32 | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/conf/Makefile.stm32 b/conf/Makefile.stm32 index 00f1cb6913..707d867861 100644 --- a/conf/Makefile.stm32 +++ b/conf/Makefile.stm32 @@ -44,10 +44,6 @@ TOOLCHAIN_DIR=$(shell dirname $(TOOLCHAIN)) GCC_BIN_DIR=$(TOOLCHAIN_DIR)/bin GCC_LIB_DIR=$(TOOLCHAIN_DIR)/arm-none-eabi/lib -# Detect if we are using the new libopencm3 or the old libopenstm32 -LIBOPENCM3_LIB=$(shell if [ -e "$(GCC_LIB_DIR)/libopencm3_stm32f1.a" ]; then echo "opencm3_stm32f1"; else echo "opencm3_stm32"; fi) -LIBOPENCM3_DEFS=$(shell if [ -e "$(GCC_LIB_DIR)/libopencm3_stm32f1.a" ]; then echo "-DSTM32F1"; fi) - # Define programs and commands. GCC_BIN_PREFIX=$(GCC_BIN_DIR)/arm-none-eabi CC = $(GCC_BIN_PREFIX)-gcc @@ -66,9 +62,14 @@ CP = $(shell which arm-none-eabi-objcopy) DMP = $(shell which arm-none-eabi-objdump) NM = $(shell which arm-none-eabi-nm) SIZE = $(shell which arm-none-eabi-size) +RM = rm GCC_LIB_DIR=$(shell dirname `which arm-none-eabi-gcc`)/../arm-none-eabi/lib endif +# Detect if we are using the new libopencm3 or the old libopenstm32 +LIBOPENCM3_LIB=$(shell if [ -e "$(GCC_LIB_DIR)/libopencm3_stm32f1.a" ]; then echo "opencm3_stm32f1"; else echo "opencm3_stm32"; fi) +LIBOPENCM3_DEFS=$(shell if [ -e "$(GCC_LIB_DIR)/libopencm3_stm32f1.a" ]; then echo "-DSTM32F1"; fi) + #first try to find OpenOCD in the path OOCD = $(shell which openocd) #if OpenOCD could not be found in the path, try the toolchain dir From 726b67bf7d118918dc559f929397b29ee2489789 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Mon, 21 Nov 2011 11:35:21 +0100 Subject: [PATCH 012/112] clean handling of "processor" attribute --- sw/tools/gen_aircraft.ml | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/sw/tools/gen_aircraft.ml b/sw/tools/gen_aircraft.ml index 7e0f1efaba..a939129326 100644 --- a/sw/tools/gen_aircraft.ml +++ b/sw/tools/gen_aircraft.ml @@ -232,12 +232,10 @@ let parse_firmware = fun makefile_ac firmware -> (* print makefile for this target *) fprintf makefile_ac "\n###########\n# -target: '%s'\n" (Xml.attrib target "name"); fprintf makefile_ac "ifeq ($(TARGET), %s)\n" (Xml.attrib target "name"); - let has_processor = - try - not (String.compare (Xml.attrib target "processor") "" = 0) - with _ -> false in - if has_processor then - fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor"); + begin (* Check for "processor" attribute *) + try fprintf makefile_ac "BOARD_PROCESSOR = %s\n" (Xml.attrib target "processor") + with _ -> () + end; List.iter (print_firmware_configure makefile_ac) config; List.iter (print_firmware_configure makefile_ac) t_config; List.iter (print_firmware_define makefile_ac) defines; From 6a64132d708b36c5fcbcc0af3e4e58d61b017151 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 22 Nov 2011 09:55:39 +0100 Subject: [PATCH 013/112] i2c test code --- conf/airframes/CDW/debug_i2c.xml | 279 ++++++++++++++++++ conf/autopilot/rotorcraft.makefile | 3 +- .../subsystems/fixedwing/autopilot.makefile | 5 +- .../subsystems/shared/i2c_select.makefile | 12 + conf/modules/i2c_abuse_test.xml | 15 + .../modules/benchmark/i2c_abuse_test.c | 245 +++++++++++++++ .../modules/benchmark/i2c_abuse_test.h | 52 ++++ 7 files changed, 606 insertions(+), 5 deletions(-) create mode 100644 conf/airframes/CDW/debug_i2c.xml create mode 100644 conf/autopilot/subsystems/shared/i2c_select.makefile create mode 100644 conf/modules/i2c_abuse_test.xml create mode 100644 sw/airborne/modules/benchmark/i2c_abuse_test.c create mode 100644 sw/airborne/modules/benchmark/i2c_abuse_test.h diff --git a/conf/airframes/CDW/debug_i2c.xml b/conf/airframes/CDW/debug_i2c.xml new file mode 100644 index 0000000000..7dd9a616eb --- /dev/null +++ b/conf/airframes/CDW/debug_i2c.xml @@ -0,0 +1,279 @@ + + + + + + + + + + + + + + + + + + + +
+ + +
+ + +
+ + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + +
+ +
+ + + +
+ + +
+ + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + + + +
+ + +
+ + +
+ +
+ + + + + + + + + + + + + + + + +
+ + +
+ + + + +
+ +
+ +
+ +
+ + + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile index 27a2e084cf..11af20574b 100644 --- a/conf/autopilot/rotorcraft.makefile +++ b/conf/autopilot/rotorcraft.makefile @@ -101,8 +101,7 @@ ap.srcs += mcu_periph/uart.c ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # I2C is needed for speed controllers and barometers on lisa -ap.srcs += mcu_periph/i2c.c -ap.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c +include $(CFG_SHARED)/i2c_select.makefile ap.srcs += $(SRC_FIRMWARE)/commands.c diff --git a/conf/autopilot/subsystems/fixedwing/autopilot.makefile b/conf/autopilot/subsystems/fixedwing/autopilot.makefile index 51d94b56a0..89e5020932 100644 --- a/conf/autopilot/subsystems/fixedwing/autopilot.makefile +++ b/conf/autopilot/subsystems/fixedwing/autopilot.makefile @@ -87,9 +87,8 @@ $(TARGET).srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_ # # I2C # -$(TARGET).srcs += mcu_periph/i2c.c -$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c - +include $(CFG_SHARED)/i2c_select.makefile + ###################################################################### ## ## COMMON FOR ALL NON-SIMULATION TARGETS diff --git a/conf/autopilot/subsystems/shared/i2c_select.makefile b/conf/autopilot/subsystems/shared/i2c_select.makefile new file mode 100644 index 0000000000..75241931af --- /dev/null +++ b/conf/autopilot/subsystems/shared/i2c_select.makefile @@ -0,0 +1,12 @@ +#generic i2c driver + +# TODO: this file was created to be able to select different driver files. Once 1 driver is selected as the best others can be removed including this file + +$(TARGET).srcs += mcu_periph/i2c.c +ifeq ($(ARCH), stm32) +$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c +#$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.rewritten.c +else +$(TARGET).srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c +endif + diff --git a/conf/modules/i2c_abuse_test.xml b/conf/modules/i2c_abuse_test.xml new file mode 100644 index 0000000000..c8c7039eb4 --- /dev/null +++ b/conf/modules/i2c_abuse_test.xml @@ -0,0 +1,15 @@ + + + +
+ +
+ + + + + + + +
+ diff --git a/sw/airborne/modules/benchmark/i2c_abuse_test.c b/sw/airborne/modules/benchmark/i2c_abuse_test.c new file mode 100644 index 0000000000..11b947b375 --- /dev/null +++ b/sw/airborne/modules/benchmark/i2c_abuse_test.c @@ -0,0 +1,245 @@ +/* + * $Id$ + * + * Copyright (C) 2009 Gautier Hattenberger + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +#include "i2c_abuse_test.h" +#include "led.h" +#include "mcu_periph/i2c.h" + +struct i2c_transaction i2c_test1; +struct i2c_transaction i2c_test2; + +uint8_t i2c_abuse_test_counter = 0; +uint16_t i2c_abuse_test_bitrate = 1000; + +void init_i2c_abuse_test(void) { + //LED_INIT(DEMO_MODULE_LED); + //LED_OFF(DEMO_MODULE_LED); + + i2c_test1.status = I2CTransSuccess; + i2c_test1.slave_addr = 0x3C; + + i2c_abuse_test_counter = 0; + i2c_abuse_test_bitrate = 10000; + + i2c_test2.status = I2CTransSuccess; + +} + +static void i2c_abuse_send_transaction(uint8_t _init) +{ + + i2c_test1.slave_addr = 0x3C; + i2c_test1.len_w = 0; + i2c_test1.len_r = 0; + + switch (_init) + { + case 1: + i2c_test1.type = I2CTransTx; + i2c_test1.buf[0] = 0x00; // set to rate to 50Hz + i2c_test1.buf[1] = 0x00 | (0x06 << 2); + i2c_test1.buf[2] = 0x01<<5; + i2c_test1.buf[3] = 0x00; + i2c_test1.len_w = 4; + i2c_submit(&i2c2,&i2c_test1); + break; + case 2: + i2c_test1.type = I2CTransTx; + i2c_test1.buf[0] = 0x01; // set to gain to 1 Gauss + i2c_test1.buf[1] = 0x01<<5; + i2c_test1.len_w = 2; + i2c_submit(&i2c2,&i2c_test1); + break; + case 3: + i2c_test1.type = I2CTransTx; + i2c_test1.buf[0] = 0x00; // set to continuous mode + i2c_test1.len_w = 1; + i2c_submit(&i2c2,&i2c_test1); + break; + case 4: + i2c_test1.type = I2CTransRx; + i2c_test1.len_r = 1; + i2c_submit(&i2c2,&i2c_test1); + break; + case 5: + i2c_test1.type = I2CTransRx; + i2c_test1.len_r = 2; + i2c_submit(&i2c2,&i2c_test1); + break; + case 6: + i2c_test1.type = I2CTransRx; + i2c_test1.len_r = 3; + i2c_submit(&i2c2,&i2c_test1); + break; + case 7: + i2c_test1.type = I2CTransRx; + i2c_test1.len_r = 4; + i2c_submit(&i2c2,&i2c_test1); + break; + case 8: + i2c_test1.type = I2CTransRx; + i2c_test1.len_r = 5; + i2c_submit(&i2c2,&i2c_test1); + break; + case 9: + // bad addr + i2c_test1.slave_addr = 0x3C + 2; + i2c_test1.type = I2CTransTx; + i2c_test1.len_w = 1; + i2c_submit(&i2c2,&i2c_test1); + break; + case 10: + // 2 consecutive + i2c_test1.type = I2CTransTx; + i2c_test1.buf[0] = 0x00; // set to continuous mode + i2c_test1.len_w = 1; + i2c_submit(&i2c2,&i2c_test1); + break; + case 11: + i2c_test1.slave_addr = 0x3C; + i2c_test1.type = I2CTransTxRx; + i2c_test1.len_r = 1; + i2c_test1.len_w = 1; + i2c_test1.buf[0] = 0x03; + i2c_submit(&i2c2, &i2c_test1); + break; + case 12: + i2c_test1.slave_addr = 0x3C; + i2c_test1.type = I2CTransTxRx; + i2c_test1.len_r = 2; + i2c_test1.len_w = 1; + i2c_test1.buf[0] = 0x03; + i2c_submit(&i2c2, &i2c_test1); + break; + case 13: + i2c_test1.slave_addr = 0x3C; + i2c_test1.type = I2CTransTxRx; + i2c_test1.len_r = 3; + i2c_test1.len_w = 1; + i2c_test1.buf[0] = 0x03; + i2c_submit(&i2c2, &i2c_test1); + break; + case 14: + i2c_test1.slave_addr = 0x3C; + i2c_test1.type = I2CTransTxRx; + i2c_test1.len_r = 4; + i2c_test1.len_w = 1; + i2c_test1.buf[0] = 0x03; + i2c_submit(&i2c2, &i2c_test1); + break; + case 15: + i2c_test1.slave_addr = 0x3C; + i2c_test1.type = I2CTransTxRx; + i2c_test1.len_r = 4; + i2c_test1.len_w = 2; + i2c_test1.buf[0] = 0x03; + i2c_submit(&i2c2, &i2c_test1); + break; + default: + i2c_test1.slave_addr = 0x3C; + i2c_test1.type = I2CTransTxRx; + i2c_test1.len_r = 5; + i2c_test1.len_w = 1; + i2c_test1.buf[0] = 0x03; + i2c_submit(&i2c2, &i2c_test1); + } +} + + +void event_i2c_abuse_test(void) +{ + if (i2c_idle(&i2c1)) + { + LED_ON(7); // green = idle + LED_OFF(6); + } + else + { + LED_ON(6); // red = busy + LED_OFF(7); + } + + if (i2c_idle(&i2c2)) + { + LED_ON(5); // green = idle + LED_OFF(4); + } + else + { + LED_ON(4); // red = busy + LED_OFF(5); + } + + // Wait for I2C transaction object to be released by the I2C driver before changing anything + if ((i2c_abuse_test_counter < 12) && (i2c_abuse_test_counter > 3)) + { + if ((i2c_test2.status == I2CTransFailed) || (i2c_test2.status == I2CTransSuccess)) + { + //i2c_test2.slave_addr = 0x90; + i2c_test2.type = I2CTransRx; + i2c_test2.slave_addr = 0x92; + i2c_test2.len_r = 2; + i2c_submit(&i2c2,&i2c_test2); + } + } + + + if ((i2c_test1.status == I2CTransFailed) || (i2c_test1.status == I2CTransSuccess)) + { + if (i2c_abuse_test_counter < 16) + { + i2c_abuse_test_counter++; + } + else + { + // wait until ready: + if (i2c_idle(&i2c2)) + { + i2c_abuse_test_counter = 1; + + i2c_setbitrate(&i2c2, i2c_abuse_test_bitrate); + + i2c_abuse_test_bitrate += 17000; + if (i2c_abuse_test_bitrate > 500000) + { + i2c_abuse_test_bitrate -= 500000; + } + LED_TOGGLE(4); + } + } + + if (i2c_abuse_test_counter < 16) + { + i2c_abuse_send_transaction( i2c_abuse_test_counter ); + LED_TOGGLE(5); + } + } +} + +void periodic_50Hz_i2c_abuse_test(void) { + // LED_TOGGLE(DEMO_MODULE_LED); +} + + + diff --git a/sw/airborne/modules/benchmark/i2c_abuse_test.h b/sw/airborne/modules/benchmark/i2c_abuse_test.h new file mode 100644 index 0000000000..e6e7b0634a --- /dev/null +++ b/sw/airborne/modules/benchmark/i2c_abuse_test.h @@ -0,0 +1,52 @@ +/* + * $Id$ + * + * Copyright (C) 2009 C. De Wagter + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \file I2C_ABUSE_TEST_module.h + * + * Total I2C Abuse: + * + * -all transaction types: T1 T2 T3 T4 R1 R2 R3 R4 T1R1 T2R1 T1R2 T1R3 T1R4 T1R5 T2R5 + * -all bitrates: 1k (way too slow) to 1M (way to fast) + * -occasional Short circuit (simulate bus capacitance or EMI errors) + * -variable bus load: from empty to full stack + * + * -Connect LED to MosFet that pulls-down the SCL and SDA lines + */ + +#ifndef I2C_ABUSE_TEST_MODULE_H +#define I2C_ABUSE_TEST_MODULE_H + +#ifndef I2C_ABUSE_SHORT_SCL_LED +#define I2C_ABUSE_SHORT_SCL_LED 2 +#endif + +#ifndef I2C_ABUSE_SHORT_SDA_LED +#define I2C_ABUSE_SHORT_SDA_LED 3 +#endif + +void init_i2c_abuse_test(void); +void event_i2c_abuse_test(void); +void periodic_50Hz_i2c_abuse_test(void); + +#endif From a1c9e89aab4526535c7d6ea8b9829500ffe06164 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 22 Nov 2011 09:57:18 +0100 Subject: [PATCH 014/112] Fix trailing whitespaces --- .../TU_Delft/EasyStartPanTiltCHIMU_SPI.xml | 2 +- conf/airframes/TU_Delft/skywalkerfiber.xml | 14 +++++++------- .../subsystems/fixedwing/autopilot.makefile | 2 +- conf/modules/gps_ubx_ucenter.xml | 2 +- sw/airborne/arch/stm32/sys_time_hw.h | 2 +- sw/airborne/modules/benchmark/i2c_abuse_test.c | 8 ++++---- sw/airborne/modules/gps/gps_ubx_ucenter.c | 8 ++++---- sw/airborne/modules/gps/gps_ubx_ucenter.h | 2 +- sw/airborne/modules/ins/ins_chimu_spi.c | 4 ++-- 9 files changed, 22 insertions(+), 22 deletions(-) diff --git a/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml b/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml index 9286e53a56..96d2fce242 100644 --- a/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml +++ b/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml @@ -1,6 +1,6 @@ - diff --git a/conf/airframes/TU_Delft/skywalkerfiber.xml b/conf/airframes/TU_Delft/skywalkerfiber.xml index 000a3c7c25..a962c1f226 100644 --- a/conf/airframes/TU_Delft/skywalkerfiber.xml +++ b/conf/airframes/TU_Delft/skywalkerfiber.xml @@ -1,6 +1,6 @@ - + + @@ -85,7 +85,7 @@ - + @@ -167,7 +167,7 @@ - + @@ -250,7 +250,7 @@ - +
@@ -272,7 +272,7 @@
- +
diff --git a/conf/autopilot/subsystems/fixedwing/autopilot.makefile b/conf/autopilot/subsystems/fixedwing/autopilot.makefile index 89e5020932..25687b7151 100644 --- a/conf/autopilot/subsystems/fixedwing/autopilot.makefile +++ b/conf/autopilot/subsystems/fixedwing/autopilot.makefile @@ -88,7 +88,7 @@ $(TARGET).srcs += math/pprz_geodetic_int.c math/pprz_geodetic_float.c math/pprz_ # I2C # include $(CFG_SHARED)/i2c_select.makefile - + ###################################################################### ## ## COMMON FOR ALL NON-SIMULATION TARGETS diff --git a/conf/modules/gps_ubx_ucenter.xml b/conf/modules/gps_ubx_ucenter.xml index 063d4bc866..883ecbd0d8 100644 --- a/conf/modules/gps_ubx_ucenter.xml +++ b/conf/modules/gps_ubx_ucenter.xml @@ -7,7 +7,7 @@ -configures all the messages, and the rates -automatic baudrate detection - Warning: you still need to tell the driver + Warning: you still need to tell the driver a) which paparazzi uart you use b) inside the ublox gps there are also many ports. the tiny/ppzgps use ublox_internal_port1 but if for instance you use a LS-SAM or I2C device you need to configure: diff --git a/sw/airborne/arch/stm32/sys_time_hw.h b/sw/airborne/arch/stm32/sys_time_hw.h index cc74f25896..9d88a69d8c 100644 --- a/sw/airborne/arch/stm32/sys_time_hw.h +++ b/sw/airborne/arch/stm32/sys_time_hw.h @@ -75,7 +75,7 @@ static inline void sys_time_usleep(uint32_t us) { { if (sys_time_period_elapsed) ready--; sys_time_periodic(); - } + } } #endif /* SYS_TIME_HW_H */ diff --git a/sw/airborne/modules/benchmark/i2c_abuse_test.c b/sw/airborne/modules/benchmark/i2c_abuse_test.c index 11b947b375..7a9b078caa 100644 --- a/sw/airborne/modules/benchmark/i2c_abuse_test.c +++ b/sw/airborne/modules/benchmark/i2c_abuse_test.c @@ -156,7 +156,7 @@ static void i2c_abuse_send_transaction(uint8_t _init) i2c_test1.buf[0] = 0x03; i2c_submit(&i2c2, &i2c_test1); break; - default: + default: i2c_test1.slave_addr = 0x3C; i2c_test1.type = I2CTransTxRx; i2c_test1.len_r = 5; @@ -167,7 +167,7 @@ static void i2c_abuse_send_transaction(uint8_t _init) } -void event_i2c_abuse_test(void) +void event_i2c_abuse_test(void) { if (i2c_idle(&i2c1)) { @@ -204,7 +204,7 @@ void event_i2c_abuse_test(void) } } - + if ((i2c_test1.status == I2CTransFailed) || (i2c_test1.status == I2CTransSuccess)) { if (i2c_abuse_test_counter < 16) @@ -231,7 +231,7 @@ void event_i2c_abuse_test(void) if (i2c_abuse_test_counter < 16) { - i2c_abuse_send_transaction( i2c_abuse_test_counter ); + i2c_abuse_send_transaction( i2c_abuse_test_counter ); LED_TOGGLE(5); } } diff --git a/sw/airborne/modules/gps/gps_ubx_ucenter.c b/sw/airborne/modules/gps/gps_ubx_ucenter.c index 7abe6112bb..aa56a5395c 100644 --- a/sw/airborne/modules/gps/gps_ubx_ucenter.c +++ b/sw/airborne/modules/gps/gps_ubx_ucenter.c @@ -325,14 +325,14 @@ static inline void gps_ubx_ucenter_enable_msg(uint8_t class, uint8_t id, uint8_t #undef GOT_PAYLOAD #include "downlink.h" -static bool_t gps_ubx_ucenter_configure(uint8_t nr) +static bool_t gps_ubx_ucenter_configure(uint8_t nr) { // Store the reply of the last configuration step and reset if (nr < GPS_UBX_UCENTER_CONFIG_STEPS) gps_ubx_ucenter.replies[nr] = gps_ubx_ucenter.reply; - + gps_ubx_ucenter.reply = GPS_UBX_UCENTER_REPLY_NONE; - + switch (nr) { case 0: UbxSend_MON_GET_VER(); @@ -355,7 +355,7 @@ static bool_t gps_ubx_ucenter_configure(uint8_t nr) DOWNLINK_SEND_DEBUG(DefaultChannel,6,gps_ubx_ucenter.replies); ////////////////////////////////// - // Actual configuration start + // Actual configuration start // Use old baudrate to issue a baudrate change command gps_ubx_ucenter_config_port(); diff --git a/sw/airborne/modules/gps/gps_ubx_ucenter.h b/sw/airborne/modules/gps/gps_ubx_ucenter.h index 50f4300afc..a14e149297 100644 --- a/sw/airborne/modules/gps/gps_ubx_ucenter.h +++ b/sw/airborne/modules/gps/gps_ubx_ucenter.h @@ -30,7 +30,7 @@ /** U-Center Variables */ #define GPS_UBX_UCENTER_CONFIG_STEPS 17 -struct gps_ubx_ucenter_struct +struct gps_ubx_ucenter_struct { uint8_t status; uint8_t reply; diff --git a/sw/airborne/modules/ins/ins_chimu_spi.c b/sw/airborne/modules/ins/ins_chimu_spi.c index 87dd9f519f..1c4c0e0b81 100644 --- a/sw/airborne/modules/ins/ins_chimu_spi.c +++ b/sw/airborne/modules/ins/ins_chimu_spi.c @@ -108,9 +108,9 @@ void ins_periodic_task( void ) float gps_speed = 0; - if (gps.fix == GPS_FIX_3D) + if (gps.fix == GPS_FIX_3D) { - gps_speed = gps.speed_3d/100.; + gps_speed = gps.speed_3d/100.; } gps_speed = FloatSwap(gps_speed); From 3bec1f933249e8118a0db49319021e1d86140485 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 22 Nov 2011 16:19:32 +0100 Subject: [PATCH 015/112] Whitespaces --- sw/airborne/firmwares/fixedwing/main_fbw.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 7b70a8f900..e5e2ffc5b5 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -152,7 +152,7 @@ void event_task_fbw( void) { { pprz_t trimmed_commands[COMMANDS_NB]; int i; - for(i = 0; i < COMMANDS_NB; i++) trimmed_commands[i] = commands[i]; + for(i = 0; i < COMMANDS_NB; i++) trimmed_commands[i] = commands[i]; #ifdef COMMAND_ROLL trimmed_commands[COMMAND_ROLL] += command_roll_trim; From a9f42a98e880dc0d41703f82c88f19c45bcafef7 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 23 Nov 2011 14:09:05 +0100 Subject: [PATCH 016/112] include i2c in main file --- conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile | 2 -- conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile | 2 -- conf/autopilot/subsystems/rotorcraft/actuators_skiron.makefile | 2 -- 3 files changed, 6 deletions(-) diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile index e31987e894..45fd6aaf54 100644 --- a/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile +++ b/conf/autopilot/subsystems/rotorcraft/actuators_asctec.makefile @@ -15,6 +15,4 @@ endif # Simulator sim.srcs += $(SRC_FIRMWARE)/actuators/actuators_asctec.c sim.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=150 -DI2C0_SCLH=150 -DI2C0_VIC_SLOT=11 -sim.srcs += mcu_periph/i2c.c -sim.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile index a55d0e4313..5922e9c2ce 100644 --- a/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile +++ b/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile @@ -51,5 +51,3 @@ endif sim.srcs += $(SRC_FIRMWARE)/actuators/supervision.c sim.srcs += $(SRC_FIRMWARE)/actuators/actuators_mkk.c sim.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=$(MKK_I2C_SCL_TIME) -DI2C0_SCLH=$(MKK_I2C_SCL_TIME) -DI2C0_VIC_SLOT=10 -DACTUATORS_MKK_DEVICE=i2c1 -sim.srcs += mcu_periph/i2c.c -sim.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_skiron.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_skiron.makefile index 1db87848db..b46487f875 100644 --- a/conf/autopilot/subsystems/rotorcraft/actuators_skiron.makefile +++ b/conf/autopilot/subsystems/rotorcraft/actuators_skiron.makefile @@ -50,6 +50,4 @@ endif sim.srcs += $(SRC_FIRMWARE)/actuators/supervision.c sim.srcs += $(SRC_FIRMWARE)/actuators/actuators_skiron.c sim.CFLAGS += -DUSE_I2C0 -DI2C0_SCLL=$(SKIRON_I2C_SCL_TIME) -DI2C0_SCLH=$(SKIRON_I2C_SCL_TIME) -DI2C0_VIC_SLOT=10 -DACTUATORS_MKK_DEVICE=i2c0 -sim.srcs += mcu_periph/i2c.c -sim.srcs += $(SRC_ARCH)/mcu_periph/i2c_arch.c From 3210ec03c975c0de7e260c00819387335bade1b1 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 23 Nov 2011 14:22:42 +0100 Subject: [PATCH 017/112] i2c added in actuator file --- conf/autopilot/rotorcraft.makefile | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile index 11af20574b..c8e4b37502 100644 --- a/conf/autopilot/rotorcraft.makefile +++ b/conf/autopilot/rotorcraft.makefile @@ -101,7 +101,9 @@ ap.srcs += mcu_periph/uart.c ap.srcs += $(SRC_ARCH)/mcu_periph/uart_arch.c # I2C is needed for speed controllers and barometers on lisa -include $(CFG_SHARED)/i2c_select.makefile +ifeq ($(TARGET), ap) + include $(CFG_SHARED)/i2c_select.makefile +endif ap.srcs += $(SRC_FIRMWARE)/commands.c From 316ce9d6caaedcf598c748de7050770d52ad4de3 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Wed, 23 Nov 2011 14:39:22 +0100 Subject: [PATCH 018/112] all rotorcraft sim stuff in fdm_nps.makefile --- conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile b/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile index 491150d7eb..00b92d675e 100644 --- a/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile +++ b/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile @@ -63,6 +63,11 @@ sim.srcs += firmwares/rotorcraft/main.c sim.srcs += mcu.c sim.srcs += $(SRC_ARCH)/mcu_arch.c +ifeq ($(TARGET), sim) + include $(CFG_SHARED)/i2c_select.makefile +endif + + sim.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC((1./512.))' # -DTIME_LED=1 #sim.CFLAGS += -DUSE_LED From 4de4dcb1fa8f23900b0126c1961e86c6753f7235 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Wed, 23 Nov 2011 14:58:38 +0100 Subject: [PATCH 019/112] modify ads1114 driver to use 2 modules (same i2c bus for now) add airspeed_ads1114 module modify baro_board module (baro for umarim) to use airspeed when airspeed_ads1114 is loaded --- conf/airframes/ENAC/fixed-wing/weasel.xml | 4 + conf/modules/airspeed_ads1114.xml | 18 +++ conf/modules/baro_board.xml | 1 + sw/airborne/boards/umarim/baro_board.c | 6 +- sw/airborne/boards/umarim/baro_board.h | 49 ++++++- .../modules/sensors/airspeed_ads1114.c | 37 +++++ .../modules/sensors/airspeed_ads1114.h | 32 ++++ sw/airborne/peripherals/ads1114.c | 46 ++++-- sw/airborne/peripherals/ads1114.h | 138 +++++++++++++----- 9 files changed, 272 insertions(+), 59 deletions(-) create mode 100644 conf/modules/airspeed_ads1114.xml create mode 100644 sw/airborne/modules/sensors/airspeed_ads1114.c create mode 100644 sw/airborne/modules/sensors/airspeed_ads1114.h diff --git a/conf/airframes/ENAC/fixed-wing/weasel.xml b/conf/airframes/ENAC/fixed-wing/weasel.xml index 827a08b350..d911596b30 100644 --- a/conf/airframes/ENAC/fixed-wing/weasel.xml +++ b/conf/airframes/ENAC/fixed-wing/weasel.xml @@ -10,6 +10,8 @@ + + @@ -40,6 +42,8 @@ + + diff --git a/conf/modules/airspeed_ads1114.xml b/conf/modules/airspeed_ads1114.xml new file mode 100644 index 0000000000..b75f51a072 --- /dev/null +++ b/conf/modules/airspeed_ads1114.xml @@ -0,0 +1,18 @@ + + + + + +
+ +
+ + + + + + + +
+ + diff --git a/conf/modules/baro_board.xml b/conf/modules/baro_board.xml index 32ce2698ad..4ace2ff541 100644 --- a/conf/modules/baro_board.xml +++ b/conf/modules/baro_board.xml @@ -12,6 +12,7 @@ + diff --git a/sw/airborne/boards/umarim/baro_board.c b/sw/airborne/boards/umarim/baro_board.c index c5f2a97398..a63fa457f1 100644 --- a/sw/airborne/boards/umarim/baro_board.c +++ b/sw/airborne/boards/umarim/baro_board.c @@ -55,7 +55,7 @@ void baro_init( void ) { ads1114_init(); baro.status = BS_UNINITIALIZED; baro.absolute = 0; - baro.differential = 0; /* not handled on this board */ + baro.differential = 0; /* not handled on this board, use extra module (ex: airspeed_ads1114) */ #ifdef USE_BARO_AS_ALTIMETER baro_alt = 0.; baro_alt_offset = 0.; @@ -66,7 +66,7 @@ void baro_init( void ) { void baro_periodic( void ) { #ifdef USE_BARO_AS_ALTIMETER - if (baro.status == BS_UNINITIALIZED && ads1114_data_available) { + if (baro.status == BS_UNINITIALIZED && BARO_ABS_ADS.data_available) { // IIR filter to compute an initial offset baro_alt_offset = (OFFSET_FILTER * baro_alt_offset + (float)baro.absolute) / (OFFSET_FILTER + 1); // decrease init counter @@ -75,7 +75,7 @@ void baro_periodic( void ) { } #endif // Read the ADC - ads1114_read(); + ads1114_read(&BARO_ABS_ADS); } void baro_downlink_raw( void ) diff --git a/sw/airborne/boards/umarim/baro_board.h b/sw/airborne/boards/umarim/baro_board.h index 26d27b29d2..e74b52c77d 100644 --- a/sw/airborne/boards/umarim/baro_board.h +++ b/sw/airborne/boards/umarim/baro_board.h @@ -35,6 +35,11 @@ #define BARO_FILTER_GAIN 5 +/* There is no differential pressure on the board but + * it can be available from an external sensor + * */ +#define DIFF_FILTER_GAIN 5 + #ifdef USE_BARO_AS_ALTIMETER extern float baro_alt; extern float baro_alt_offset; @@ -43,15 +48,45 @@ extern float baro_alt_offset; extern void baro_downlink_raw( void ); +#define BARO_ABS_ADS ads1114_1 + +#define BaroAbs(_ads, _handler) { \ + if (_ads.data_available) { \ + baro.absolute = (baro.absolute + BARO_FILTER_GAIN*Ads1114GetValue(_ads)) / (BARO_FILTER_GAIN+1); \ + if (baro.status == BS_RUNNING) { \ + _handler(); \ + _ads.data_available = FALSE; \ + } \ + } \ +} + +#ifndef BaroDiff // Allow custom redefinition ? + +#if USE_BARO_DIFF + +#ifndef BARO_DIFF_ADS +#define BARO_DIFF_ADS ads1114_2 +#endif +#define BaroDiff(_ads, _handler) { \ + if (_ads.data_available) { \ + baro.differential = (baro.differential + DIFF_FILTER_GAIN*Ads1114GetValue(_ads)) / (DIFF_FILTER_GAIN+1); \ + if (baro.status == BS_RUNNING) { \ + _handler(); \ + _ads.data_available = FALSE; \ + } \ + } \ +} + +#else // Not using differential with ADS1114 +#define BaroDiff(_a, _h) {} +#endif + +#endif // ifndef BaroDiff + #define BaroEvent(_b_abs_handler, _b_diff_handler) { \ Ads1114Event(); \ - if (ads1114_data_available) { \ - baro.absolute = (baro.absolute + BARO_FILTER_GAIN*Ads1114GetValue()) / (BARO_FILTER_GAIN+1); \ - if (baro.status == BS_RUNNING) { \ - _b_abs_handler(); \ - ads1114_data_available = FALSE; \ - } \ - } \ + BaroAbs(BARO_ABS_ADS,_b_abs_handler); \ + BaroDiff(BARO_DIFF_ADS,_b_diff_handler); \ } #endif // BOARDS_UMARIM_BARO_H diff --git a/sw/airborne/modules/sensors/airspeed_ads1114.c b/sw/airborne/modules/sensors/airspeed_ads1114.c new file mode 100644 index 0000000000..b472beb4ad --- /dev/null +++ b/sw/airborne/modules/sensors/airspeed_ads1114.c @@ -0,0 +1,37 @@ +/* + * Copyright (C) 2011 Gautier Hattenberger + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/* + * Module to extend the baro_board module with an airspeed sensor + * Init and event functions are handled by the baro_board module + */ + +#include "modules/sensors/airspeed_ads1114.h" +#include "subsystems/sensors/baro.h" +#include "baro_board.h" + +void airspeed_periodic(void) { + ads1114_read(&BARO_DIFF_ADS); +} + + + diff --git a/sw/airborne/modules/sensors/airspeed_ads1114.h b/sw/airborne/modules/sensors/airspeed_ads1114.h new file mode 100644 index 0000000000..90bbce344f --- /dev/null +++ b/sw/airborne/modules/sensors/airspeed_ads1114.h @@ -0,0 +1,32 @@ +/* + * Copyright (C) 2011 Gautier Hattenberger + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/* + * Module to extend the baro_board module with an airspeed sensor + */ + +#ifndef AIRSPEED_ADS1114_H +#define AIRSPEED_ADS1114_H + +extern void airspeed_periodic(void); + +#endif diff --git a/sw/airborne/peripherals/ads1114.c b/sw/airborne/peripherals/ads1114.c index 0c91981d26..3e6950ea71 100644 --- a/sw/airborne/peripherals/ads1114.c +++ b/sw/airborne/peripherals/ads1114.c @@ -27,28 +27,44 @@ #include "peripherals/ads1114.h" -struct i2c_transaction ads1114_trans; - -bool_t ads1114_config_done; -bool_t ads1114_data_available; +#if USE_ADS1114_1 +struct ads1114_periph ads1114_1; +#endif +#if USE_ADS1114_2 +struct ads1114_periph ads1114_2; +#endif void ads1114_init( void ) { - /* configure the ads1114 */ - ads1114_trans.buf[0] = ADS1114_POINTER_CONFIG_REG; - ads1114_trans.buf[1] = ADS1114_CONFIG_MSB; - ads1114_trans.buf[2] = ADS1114_CONFIG_LSB; - I2CTransmit(ADS1114_I2C_DEVICE, ads1114_trans, ADS1114_I2C_ADDR, 3); - ads1114_config_done = FALSE; - ads1114_data_available = FALSE; + /* configure the ads1114_1 */ +#if USE_ADS1114_1 + ads1114_1.i2c_addr = ADS1114_1_I2C_ADDR; + ads1114_1.trans.buf[0] = ADS1114_POINTER_CONFIG_REG; + ads1114_1.trans.buf[1] = ADS1114_1_CONFIG_MSB; + ads1114_1.trans.buf[2] = ADS1114_1_CONFIG_LSB; + I2CTransmit(ADS1114_I2C_DEVICE, ads1114_1.trans, ADS1114_1_I2C_ADDR, 3); + ads1114_1.config_done = FALSE; + ads1114_1.data_available = FALSE; +#endif + + /* configure the ads1114_2 */ +#if USE_ADS1114_2 + ads1114_2.i2c_addr = ADS1114_2_I2C_ADDR; + ads1114_2.trans.buf[0] = ADS1114_POINTER_CONFIG_REG; + ads1114_2.trans.buf[1] = ADS1114_2_CONFIG_MSB; + ads1114_2.trans.buf[2] = ADS1114_2_CONFIG_LSB; + I2CTransmit(ADS1114_I2C_DEVICE, ads1114_2.trans, ADS1114_2_I2C_ADDR, 3); + ads1114_2.config_done = FALSE; + ads1114_2.data_available = FALSE; +#endif } -void ads1114_read( void ) { +void ads1114_read( struct ads1114_periph * p ) { // Config done with success // start new reading when previous is done (and read if success) - if (ads1114_config_done && ads1114_trans.status == I2CTransDone) { - ads1114_trans.buf[0] = ADS1114_POINTER_CONV_REG; - I2CTransceive(ADS1114_I2C_DEVICE, ads1114_trans, ADS1114_I2C_ADDR, 1, 2); + if (p->config_done && p->trans.status == I2CTransDone) { + p->trans.buf[0] = ADS1114_POINTER_CONV_REG; + I2CTransceive(ADS1114_I2C_DEVICE, p->trans, p->i2c_addr, 1, 2); } } diff --git a/sw/airborne/peripherals/ads1114.h b/sw/airborne/peripherals/ads1114.h index 866fce50db..550cd7dfb4 100644 --- a/sw/airborne/peripherals/ads1114.h +++ b/sw/airborne/peripherals/ads1114.h @@ -32,66 +32,136 @@ /* I2C slave address */ -#define ADS1114_I2C_ADDR 0x90 // slave address byte (I2c address(7bits) + R/W @ 0) +#ifndef ADS1114_1_I2C_ADDR +#define ADS1114_1_I2C_ADDR 0x90 // slave address byte (I2c address(7bits) + R/W @ 0) +#endif +#ifndef ADS1114_2_I2C_ADDR +#define ADS1114_2_I2C_ADDR 0x92 // slave address byte (I2c address(7bits) + R/W @ 0) +#endif /* I2C conf register */ #define ADS1114_POINTER_CONV_REG 0x00 // access to the Conversion register (16bits) #define ADS1114_POINTER_CONFIG_REG 0x01 // access to the Configuration register (16bits) -/* ADS1114 default conf */ -#ifndef ADS1114_OS -#define ADS1114_OS 0x0 // Operational status +/* ADS1114_1 default conf */ +#ifndef ADS1114_1_OS +#define ADS1114_1_OS 0x0 // Operational status #endif -#ifndef ADS1114_MUX -#define ADS1114_MUX 0x0 // Input multiplexer +#ifndef ADS1114_1_MUX +#define ADS1114_1_MUX 0x0 // Input multiplexer #endif -#ifndef ADS1114_PGA -#define ADS1114_PGA 0x3 // Programable gain amplifier (= 4 with a Full Scale of +/- 1.024V) +#ifndef ADS1114_1_PGA +#define ADS1114_1_PGA 0x3 // Programable gain amplifier (= 4 with a Full Scale of +/- 1.024V) #endif -#ifndef ADS1114_MODE -#define ADS1114_MODE 0x0 // Continuous conversion mode +#ifndef ADS1114_1_MODE +#define ADS1114_1_MODE 0x0 // Continuous conversion mode #endif -#ifndef ADS1114_DR -#define ADS1114_DR 0x4 // Data rate (128 SPS) +#ifndef ADS1114_1_DR +#define ADS1114_1_DR 0x4 // Data rate (128 SPS) #endif -#ifndef ADS1114_COMP_MODE -#define ADS1114_COMP_MODE 0x0 // Comparator mode +#ifndef ADS1114_1_COMP_MODE +#define ADS1114_1_COMP_MODE 0x0 // Comparator mode #endif -#ifndef ADS1114_COMP_POL -#define ADS1114_COMP_POL 0x0 // Comparator polarity +#ifndef ADS1114_1_COMP_POL +#define ADS1114_1_COMP_POL 0x0 // Comparator polarity #endif -#ifndef ADS1114_COMP_LAT -#define ADS1114_COMP_LAT 0x0 // Latching comparator +#ifndef ADS1114_1_COMP_LAT +#define ADS1114_1_COMP_LAT 0x0 // Latching comparator #endif -#ifndef ADS1114_COMP_QUE -#define ADS1114_COMP_QUE 0x3 // Comparator queue (disable) +#ifndef ADS1114_1_COMP_QUE +#define ADS1114_1_COMP_QUE 0x3 // Comparator queue (disable) #endif -#define ADS1114_CONFIG_MSB ((ADS1114_OS<<7)|(ADS1114_MUX<<4)|(ADS1114_PGA<<1)|(ADS1114_MODE)) -#define ADS1114_CONFIG_LSB ((ADS1114_DR<<5)|(ADS1114_COMP_MODE<<4)|(ADS1114_COMP_POL<<3)|(ADS1114_COMP_LAT<<2)|(ADS1114_COMP_QUE)) +#define ADS1114_1_CONFIG_MSB ((ADS1114_1_OS<<7)|(ADS1114_1_MUX<<4)|(ADS1114_1_PGA<<1)|(ADS1114_1_MODE)) +#define ADS1114_1_CONFIG_LSB ((ADS1114_1_DR<<5)|(ADS1114_1_COMP_MODE<<4)|(ADS1114_1_COMP_POL<<3)|(ADS1114_1_COMP_LAT<<2)|(ADS1114_1_COMP_QUE)) + +/* ADS1114_1 default conf */ +#ifndef ADS1114_2_OS +#define ADS1114_2_OS 0x0 // Operational status +#endif +#ifndef ADS1114_2_MUX +#define ADS1114_2_MUX 0x0 // Input multiplexer +#endif +#ifndef ADS1114_2_PGA +#define ADS1114_2_PGA 0x3 // Programable gain amplifier (= 4 with a Full Scale of +/- 1.024V) +#endif +#ifndef ADS1114_2_MODE +#define ADS1114_2_MODE 0x0 // Continuous conversion mode +#endif +#ifndef ADS1114_2_DR +#define ADS1114_2_DR 0x4 // Data rate (128 SPS) +#endif +#ifndef ADS1114_2_COMP_MODE +#define ADS1114_2_COMP_MODE 0x0 // Comparator mode +#endif +#ifndef ADS1114_2_COMP_POL +#define ADS1114_2_COMP_POL 0x0 // Comparator polarity +#endif +#ifndef ADS1114_2_COMP_LAT +#define ADS1114_2_COMP_LAT 0x0 // Latching comparator +#endif +#ifndef ADS1114_2_COMP_QUE +#define ADS1114_2_COMP_QUE 0x3 // Comparator queue (disable) +#endif + +#define ADS1114_2_CONFIG_MSB ((ADS1114_2_OS<<7)|(ADS1114_2_MUX<<4)|(ADS1114_2_PGA<<1)|(ADS1114_2_MODE)) +#define ADS1114_2_CONFIG_LSB ((ADS1114_2_DR<<5)|(ADS1114_2_COMP_MODE<<4)|(ADS1114_2_COMP_POL<<3)|(ADS1114_2_COMP_LAT<<2)|(ADS1114_2_COMP_QUE)) /* Default I2C device */ +// FIXME all ads on the same device for now #ifndef ADS1114_I2C_DEVICE #define ADS1114_I2C_DEVICE i2c1 #endif -extern struct i2c_transaction ads1114_trans; -extern bool_t ads1114_config_done; -extern bool_t ads1114_data_available; +struct ads1114_periph { + struct i2c_transaction trans; + uint8_t i2c_addr; + bool_t config_done; + bool_t data_available; +}; + +#if USE_ADS1114_1 +extern struct ads1114_periph ads1114_1; +#endif + +#if USE_ADS1114_2 +extern struct ads1114_periph ads1114_2; +#endif extern void ads1114_init(void); -extern void ads1114_read(void); +extern void ads1114_read(struct ads1114_periph * p); -#define Ads1114Event() { \ - if (!ads1114_config_done) { \ - if (ads1114_trans.status == I2CTransSuccess) { ads1114_config_done = TRUE; ads1114_trans.status = I2CTransDone; } \ - if (ads1114_trans.status == I2CTransFailed) { ads1114_trans.status = I2CTransDone; } \ +// Generic Event Macro +#define _Ads1114Event(_p) {\ + if (!_p.config_done) { \ + if (_p.trans.status == I2CTransSuccess) { _p.config_done = TRUE; _p.trans.status = I2CTransDone; } \ + if (_p.trans.status == I2CTransFailed) { _p.trans.status = I2CTransDone; } \ } else { \ - if (ads1114_trans.status == I2CTransSuccess) { ads1114_data_available = TRUE; ads1114_trans.status = I2CTransDone; } \ - if (ads1114_trans.status == I2CTransFailed) { ads1114_trans.status = I2CTransDone; } \ - }\ + if (_p.trans.status == I2CTransSuccess) { _p.data_available = TRUE; _p.trans.status = I2CTransDone; } \ + if (_p.trans.status == I2CTransFailed) { _p.trans.status = I2CTransDone; } \ + } \ } -#define Ads1114GetValue() ((int16_t)(((int16_t)ads1114_trans.buf[0]<<8)|ads1114_trans.buf[1])) +#if USE_ADS1114_1 +#define Ads1114_1Event() _Ads1114Event(ads1114_1) +#else +#define Ads1114_1Event() {} +#endif + +#if USE_ADS1114_2 +#define Ads1114_2Event() _Ads1114Event(ads1114_2) +#else +#define Ads1114_2Event() {} +#endif + +// Final event macro +#define Ads1114Event() { \ + Ads1114_1Event(); \ + Ads1114_2Event(); \ +} + +// Get value macro +// @param ads1114 periph +#define Ads1114GetValue(_p) ((int16_t)(((int16_t)_p.trans.buf[0]<<8)|_p.trans.buf[1])) #endif // ADS_1114_H From b1c8d2af4514fd8a341628835c5eec423eb95cae Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 01:40:56 +0100 Subject: [PATCH 020/112] removed obsolete DATALINK section from airframe files --- conf/airframes/CDW/ChimuLisaFw.xml | 6 - conf/airframes/ENAC/fixed-wing/drops.xml | 4 - conf/airframes/ENAC/fixed-wing/slayer2.xml | 7 - conf/airframes/ENAC/malolo_sim.xml | 7 - .../PPZUAV/fixed-wing/kalscott_easystar.xml | 205 ------------------ conf/airframes/TU_Delft/MicrojetCDW.xml | 5 - conf/airframes/TU_Delft/Trip50A.xml | 7 - conf/airframes/TU_Delft/Trip50B.xml | 7 - conf/airframes/TU_Delft/holiday50.xml | 7 - conf/airframes/easystar_example.xml | 5 - conf/airframes/mentor_tum.xml | 7 - conf/airframes/microjet_example.xml | 6 - conf/airframes/mm/extra/press_t.xml | 5 - conf/airframes/mm/extra/probe_t.xml | 5 - conf/airframes/mm/extra/rctx.xml | 5 - conf/airframes/mm/fixed-wing/funjeteth1.xml | 5 - conf/airframes/mm/fixed-wing/funjeteth2.xml | 5 - conf/airframes/mm/fixed-wing/funjetfmi1.xml | 5 - conf/airframes/mm/fixed-wing/funjetfmi2.xml | 5 - conf/airframes/mm/fixed-wing/funjetfmi3.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi1.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi3.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi4.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi5.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi6.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi7.xml | 5 - conf/airframes/mm/fixed-wing/funjetgfi9.xml | 5 - conf/airframes/mm/fixed-wing/funjetmm2.xml | 5 - conf/airframes/mm/fixed-wing/miniwing.xml | 5 - conf/airframes/mm/fixed-wing/slowfast.xml | 5 - conf/airframes/mm/fixed-wing/twinstarmm.xml | 4 - .../airframes/{Paul => obsolete}/minimag1.xml | 0 .../mmlaas_N1_carto_cam.xml | 0 conf/airframes/test_i2c.xml | 5 - 34 files changed, 372 deletions(-) delete mode 100644 conf/airframes/PPZUAV/fixed-wing/kalscott_easystar.xml rename conf/airframes/{Paul => obsolete}/minimag1.xml (100%) rename conf/airframes/{LAAS => obsolete}/mmlaas_N1_carto_cam.xml (100%) diff --git a/conf/airframes/CDW/ChimuLisaFw.xml b/conf/airframes/CDW/ChimuLisaFw.xml index 3c7ed0971c..71aac60c58 100644 --- a/conf/airframes/CDW/ChimuLisaFw.xml +++ b/conf/airframes/CDW/ChimuLisaFw.xml @@ -154,12 +154,6 @@
-
- - -
- -
diff --git a/conf/airframes/ENAC/fixed-wing/drops.xml b/conf/airframes/ENAC/fixed-wing/drops.xml index 289865ccae..f77fb115e8 100644 --- a/conf/airframes/ENAC/fixed-wing/drops.xml +++ b/conf/airframes/ENAC/fixed-wing/drops.xml @@ -210,10 +210,6 @@ on
-
- - -
CONFIG = \"tiny_2_1.h\" diff --git a/conf/airframes/ENAC/fixed-wing/slayer2.xml b/conf/airframes/ENAC/fixed-wing/slayer2.xml index 70068d7f41..46d368aea6 100644 --- a/conf/airframes/ENAC/fixed-wing/slayer2.xml +++ b/conf/airframes/ENAC/fixed-wing/slayer2.xml @@ -188,13 +188,6 @@ - - include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile diff --git a/conf/airframes/ENAC/malolo_sim.xml b/conf/airframes/ENAC/malolo_sim.xml index 4d8c4f4cde..468d45916c 100644 --- a/conf/airframes/ENAC/malolo_sim.xml +++ b/conf/airframes/ENAC/malolo_sim.xml @@ -192,14 +192,7 @@ - - -
diff --git a/conf/airframes/PPZUAV/fixed-wing/kalscott_easystar.xml b/conf/airframes/PPZUAV/fixed-wing/kalscott_easystar.xml deleted file mode 100644 index 67c5017f07..0000000000 --- a/conf/airframes/PPZUAV/fixed-wing/kalscott_easystar.xml +++ /dev/null @@ -1,205 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- -
- - - - -
- -
- - - - - - - - - - - - - - - - - - - - -
- -
- - - - -
- -
- - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - -
- -
- - -
- -
- - - - - - - - -
- -
- - - - - -
- -
- - -
- - -CONFIG = \"tiny_2_1_1.h\" - -# Target configuration -include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile - -FLASH_MODE=IAP - -ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=1 -DUSE_MODULES -ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c - -ap.srcs += commands.c - -# Servo driver -ap.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -ap.srcs += $(SRC_ARCH)/servos_4017_hw.c actuators.c - -# Radio configuration -ap.CFLAGS += -DRADIO_CONTROL -ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c - -# Telemetry configuration -ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -DDATALINK=PPRZ -DUART1_BAUD=B57600 -ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c - -ap.CFLAGS += -DINTER_MCU -ap.srcs += inter_mcu.c - -# ADC configuration -ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 -ap.srcs += $(SRC_ARCH)/adc_hw.c - -# USE_GPS configuration -ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART0 -DGPS_LINK=Uart0 -DUART0_BAUD=B38400 -DGPS_USE_LATLONG -DGPS_LED=2 -ap.srcs += gps_ubx.c gps.c latlong.c - -ap.CFLAGS += -DUSE_INFRARED -DALT_KALMAN -ap.srcs += infrared.c estimator.c - -# Control loops -ap.CFLAGS += -DNAV -DLOITER_TRIM -ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c - -ap.srcs += subsystems/navigation/nav_line.c -ap.srcs += subsystems/navigation/nav_survey_rectangle.c - - - -# Config for SITL simulation -include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile -sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DLOITER_TRIM -DALT_KALMAN -DUSE_MODULES -sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c - - - diff --git a/conf/airframes/TU_Delft/MicrojetCDW.xml b/conf/airframes/TU_Delft/MicrojetCDW.xml index fc038e964e..a778aeb5ff 100644 --- a/conf/airframes/TU_Delft/MicrojetCDW.xml +++ b/conf/airframes/TU_Delft/MicrojetCDW.xml @@ -184,11 +184,6 @@
-
- - -
- diff --git a/conf/airframes/TU_Delft/Trip50A.xml b/conf/airframes/TU_Delft/Trip50A.xml index 857bb271f7..a37429aeb5 100644 --- a/conf/airframes/TU_Delft/Trip50A.xml +++ b/conf/airframes/TU_Delft/Trip50A.xml @@ -231,13 +231,6 @@ inline static void h_ctl_roll_loop( void ) { - -
diff --git a/conf/airframes/TU_Delft/Trip50B.xml b/conf/airframes/TU_Delft/Trip50B.xml index dab375a875..a95827c333 100644 --- a/conf/airframes/TU_Delft/Trip50B.xml +++ b/conf/airframes/TU_Delft/Trip50B.xml @@ -236,13 +236,6 @@ inline static void h_ctl_roll_loop( void ) { - -
diff --git a/conf/airframes/TU_Delft/holiday50.xml b/conf/airframes/TU_Delft/holiday50.xml index c60b9f2e2f..5a2724fbdb 100644 --- a/conf/airframes/TU_Delft/holiday50.xml +++ b/conf/airframes/TU_Delft/holiday50.xml @@ -231,13 +231,6 @@ inline static void h_ctl_roll_loop( void ) { - -
diff --git a/conf/airframes/easystar_example.xml b/conf/airframes/easystar_example.xml index be87c02e21..58c5b0c2e6 100644 --- a/conf/airframes/easystar_example.xml +++ b/conf/airframes/easystar_example.xml @@ -164,9 +164,4 @@ -
- - -
- diff --git a/conf/airframes/mentor_tum.xml b/conf/airframes/mentor_tum.xml index e7b0e7d831..df5cd797f7 100644 --- a/conf/airframes/mentor_tum.xml +++ b/conf/airframes/mentor_tum.xml @@ -208,13 +208,6 @@ - -
diff --git a/conf/airframes/microjet_example.xml b/conf/airframes/microjet_example.xml index 944c68f774..ec56ab56e9 100644 --- a/conf/airframes/microjet_example.xml +++ b/conf/airframes/microjet_example.xml @@ -157,12 +157,6 @@
-
- - -
- -
diff --git a/conf/airframes/mm/extra/press_t.xml b/conf/airframes/mm/extra/press_t.xml index 59172f27d6..3073f74886 100644 --- a/conf/airframes/mm/extra/press_t.xml +++ b/conf/airframes/mm/extra/press_t.xml @@ -174,11 +174,6 @@ -
- -
- -
diff --git a/conf/airframes/mm/extra/probe_t.xml b/conf/airframes/mm/extra/probe_t.xml index 37fd3601e2..01811ad4a0 100644 --- a/conf/airframes/mm/extra/probe_t.xml +++ b/conf/airframes/mm/extra/probe_t.xml @@ -194,11 +194,6 @@ -
- -
- -
diff --git a/conf/airframes/mm/extra/rctx.xml b/conf/airframes/mm/extra/rctx.xml index 6001747f16..da6e0d221f 100644 --- a/conf/airframes/mm/extra/rctx.xml +++ b/conf/airframes/mm/extra/rctx.xml @@ -19,11 +19,6 @@
-
- - -
- CONFIG = \"tiny_2_1.h\" diff --git a/conf/airframes/mm/fixed-wing/funjeteth1.xml b/conf/airframes/mm/fixed-wing/funjeteth1.xml index d0b9b75d5b..a65932583a 100644 --- a/conf/airframes/mm/fixed-wing/funjeteth1.xml +++ b/conf/airframes/mm/fixed-wing/funjeteth1.xml @@ -170,11 +170,6 @@ - - -
- -
diff --git a/conf/airframes/mm/fixed-wing/funjeteth2.xml b/conf/airframes/mm/fixed-wing/funjeteth2.xml index fdd700591a..ab569e0540 100644 --- a/conf/airframes/mm/fixed-wing/funjeteth2.xml +++ b/conf/airframes/mm/fixed-wing/funjeteth2.xml @@ -171,11 +171,6 @@ -
- -
- -
diff --git a/conf/airframes/mm/fixed-wing/funjetfmi1.xml b/conf/airframes/mm/fixed-wing/funjetfmi1.xml index 4941da26af..bd39cefb89 100644 --- a/conf/airframes/mm/fixed-wing/funjetfmi1.xml +++ b/conf/airframes/mm/fixed-wing/funjetfmi1.xml @@ -169,11 +169,6 @@ -
- -
- -
diff --git a/conf/airframes/mm/fixed-wing/funjetfmi2.xml b/conf/airframes/mm/fixed-wing/funjetfmi2.xml index c076a05477..6dd3339263 100644 --- a/conf/airframes/mm/fixed-wing/funjetfmi2.xml +++ b/conf/airframes/mm/fixed-wing/funjetfmi2.xml @@ -170,11 +170,6 @@
-
- - -
-
diff --git a/conf/airframes/mm/fixed-wing/funjetfmi3.xml b/conf/airframes/mm/fixed-wing/funjetfmi3.xml index 564d49b045..a0bac989c2 100644 --- a/conf/airframes/mm/fixed-wing/funjetfmi3.xml +++ b/conf/airframes/mm/fixed-wing/funjetfmi3.xml @@ -168,11 +168,6 @@ - - -
- -
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi1.xml b/conf/airframes/mm/fixed-wing/funjetgfi1.xml index 402d3614d4..e6f10ef4eb 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi1.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi1.xml @@ -168,11 +168,6 @@
-
- - -
-
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi3.xml b/conf/airframes/mm/fixed-wing/funjetgfi3.xml index 3647cddfc0..4570d819b7 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi3.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi3.xml @@ -186,11 +186,6 @@ -
- - -
- include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile diff --git a/conf/airframes/mm/fixed-wing/funjetgfi4.xml b/conf/airframes/mm/fixed-wing/funjetgfi4.xml index dd100932fc..4b2a1a8d56 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi4.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi4.xml @@ -169,11 +169,6 @@ -
- - -
-
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi5.xml b/conf/airframes/mm/fixed-wing/funjetgfi5.xml index 0731f33820..c2417140f0 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi5.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi5.xml @@ -168,11 +168,6 @@ - - -
- -
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi6.xml b/conf/airframes/mm/fixed-wing/funjetgfi6.xml index e4f607d80b..ba7035b60e 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi6.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi6.xml @@ -170,11 +170,6 @@
-
- - -
-
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi7.xml b/conf/airframes/mm/fixed-wing/funjetgfi7.xml index be48d15148..2938facb71 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi7.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi7.xml @@ -170,11 +170,6 @@ -
- - -
-
diff --git a/conf/airframes/mm/fixed-wing/funjetgfi9.xml b/conf/airframes/mm/fixed-wing/funjetgfi9.xml index aaacc21284..4a10711d40 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi9.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi9.xml @@ -168,11 +168,6 @@ - - -
- -
diff --git a/conf/airframes/mm/fixed-wing/funjetmm2.xml b/conf/airframes/mm/fixed-wing/funjetmm2.xml index 03a942f097..61b63da805 100644 --- a/conf/airframes/mm/fixed-wing/funjetmm2.xml +++ b/conf/airframes/mm/fixed-wing/funjetmm2.xml @@ -176,11 +176,6 @@
-
- - -
-
diff --git a/conf/airframes/mm/fixed-wing/miniwing.xml b/conf/airframes/mm/fixed-wing/miniwing.xml index f4c41ba9f6..18705e7491 100644 --- a/conf/airframes/mm/fixed-wing/miniwing.xml +++ b/conf/airframes/mm/fixed-wing/miniwing.xml @@ -168,11 +168,6 @@ -
- - -
- CONFIG = \"tiny_2_1.h\" diff --git a/conf/airframes/mm/fixed-wing/slowfast.xml b/conf/airframes/mm/fixed-wing/slowfast.xml index 67c62bfef9..a0e58b5052 100644 --- a/conf/airframes/mm/fixed-wing/slowfast.xml +++ b/conf/airframes/mm/fixed-wing/slowfast.xml @@ -217,11 +217,6 @@ -
- - -
- CONFIG = \"tiny_2_1.h\" diff --git a/conf/airframes/Paul/minimag1.xml b/conf/airframes/obsolete/minimag1.xml similarity index 100% rename from conf/airframes/Paul/minimag1.xml rename to conf/airframes/obsolete/minimag1.xml diff --git a/conf/airframes/LAAS/mmlaas_N1_carto_cam.xml b/conf/airframes/obsolete/mmlaas_N1_carto_cam.xml similarity index 100% rename from conf/airframes/LAAS/mmlaas_N1_carto_cam.xml rename to conf/airframes/obsolete/mmlaas_N1_carto_cam.xml diff --git a/conf/airframes/test_i2c.xml b/conf/airframes/test_i2c.xml index 53bf60d7dd..b7546315d2 100644 --- a/conf/airframes/test_i2c.xml +++ b/conf/airframes/test_i2c.xml @@ -1,10 +1,5 @@ -
- - -
- ARCH=lpc21 From 9fb515fe322026786c345c90635825c53d62b2bf Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 12:04:53 +0100 Subject: [PATCH 021/112] commented unused configure_mag in asprin driver to get rid of warning --- sw/airborne/subsystems/imu/imu_aspirin.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/imu/imu_aspirin.c b/sw/airborne/subsystems/imu/imu_aspirin.c index 86cb2a8764..bd207dadd8 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin.c +++ b/sw/airborne/subsystems/imu/imu_aspirin.c @@ -7,8 +7,8 @@ struct ImuAspirin imu_aspirin; /* initialize peripherals */ static void configure_gyro(void); -static void configure_mag(void); static void configure_accel(void); +//static void configure_mag(void); static void send_i2c_msg_with_retry(struct i2c_transaction* t) { uint8_t max_retry = 8; From c872bd87fce8ecce7e55da5bf1694337a5672d78 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 14:03:51 +0100 Subject: [PATCH 022/112] always warn about deprecated/unused bat defines --- sw/airborne/firmwares/fixedwing/main_fbw.c | 5 ----- sw/airborne/subsystems/electrical.c | 7 +++++++ 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index 40dcf65a58..7989e57433 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -48,11 +48,6 @@ #include "link_mcu.h" #endif -#ifdef MILLIAMP_PER_PERCENT -#error "deprecated MILLIAMP_PER_PERCENT --> Please use MILLIAMP_AT_FULL_THROTTLE" -#endif - - uint8_t fbw_mode; #include "inter_mcu.h" diff --git a/sw/airborne/subsystems/electrical.c b/sw/airborne/subsystems/electrical.c index 4694df4e89..c9986928c1 100644 --- a/sw/airborne/subsystems/electrical.c +++ b/sw/airborne/subsystems/electrical.c @@ -6,6 +6,13 @@ #include "generated/airframe.h" #include BOARD_CONFIG +#ifdef MILLIAMP_PER_PERCENT +#warning "deprecated MILLIAMP_PER_PERCENT --> Please use MILLIAMP_AT_FULL_THROTTLE" +#endif +#if defined BATTERY_SENS || defined BATTERY_OFFSET +#warning "BATTERY_SENS and BATTERY_OFFSET are deprecated, please remove them --> if you want to change the default use VoltageOfAdc" +#endif + struct Electrical electrical; static struct { From 7e9704edd0baf0f7601874a685fcca2f1d43ead9 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 15:05:21 +0100 Subject: [PATCH 023/112] removed obsolete MILLIAMP_PER_PERCENT and BATTERY_SENS defines in airframe files, they don't do anything anymore --- conf/airframes/CDW/debug_i2c.xml | 2 -- conf/airframes/ENAC/quadrotor/blender.xml | 1 - conf/airframes/ENAC/quadrotor/booz2_g1.xml | 2 -- conf/airframes/ENAC/quadrotor/g1_vision.xml | 2 -- conf/airframes/ENAC/quadrotor/mkk1-vision.xml | 2 -- conf/airframes/ENAC/quadrotor/mkk1.xml | 2 -- conf/airframes/ENAC/quadrotor/nova1.xml | 2 -- conf/airframes/NoVa_L.xml | 2 -- .../airframes/PPZUAV/quadrotor/ppzuav_booz2_asctec_example.xml | 2 -- conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_mkk_example.xml | 2 -- conf/airframes/Poine/booz2_a1.xml | 2 -- conf/airframes/Poine/booz2_a1p.xml | 2 -- conf/airframes/Poine/booz2_a7.xml | 2 -- conf/airframes/Poine/booz2_a8.xml | 2 -- conf/airframes/Poine/easy_glider1.xml | 1 - conf/airframes/Poine/h_hex.xml | 2 -- conf/airframes/UofAdelaide/A1000_BOOZ.xml | 2 -- conf/airframes/UofAdelaide/A1000_LISA.xml | 2 -- conf/airframes/UofAdelaide/A1000_NOVA.xml | 3 --- conf/airframes/UofAdelaide/booz2_NoVa_001_1000.xml | 3 --- conf/airframes/UofAdelaide/booz2_a1000.xml | 2 -- conf/airframes/UofAdelaide/lisa_a1000.xml | 2 -- conf/airframes/booz2_flixr.xml | 1 - conf/airframes/booz2_ppzuav.xml | 3 --- conf/airframes/easy_glider_example.xml | 1 - conf/airframes/esden/jt_lisam.xml | 2 -- conf/airframes/esden/lisa_asctec.xml | 2 -- conf/airframes/esden/lisa_asctec_aspirin.xml | 2 -- conf/airframes/esden/lisa_m_pwm.xml | 2 -- conf/airframes/esden/lisa_pwm_aspirin.xml | 2 -- conf/airframes/esden/synerani_4B.xml | 2 -- conf/airframes/mm/extra/rctx.xml | 1 - conf/airframes/mm/fixed-wing/funjetgfi3.xml | 1 - conf/airframes/mm/fixed-wing/funjetgfi4.xml | 1 - conf/airframes/mm/hangar/black_one.xml | 1 - conf/airframes/mm/hangar/glass_one1.xml | 1 - conf/airframes/mm/hangar/glass_one2.xml | 1 - conf/airframes/mm/hangar/glass_one3.xml | 1 - conf/airframes/mm/hangar/mac06a.xml | 1 - conf/airframes/mm/hangar/red_one.xml | 1 - conf/airframes/mm/rotor/qmk1.xml | 2 -- 41 files changed, 72 deletions(-) diff --git a/conf/airframes/CDW/debug_i2c.xml b/conf/airframes/CDW/debug_i2c.xml index 7dd9a616eb..db334d1447 100644 --- a/conf/airframes/CDW/debug_i2c.xml +++ b/conf/airframes/CDW/debug_i2c.xml @@ -74,9 +74,7 @@
- -
diff --git a/conf/airframes/ENAC/quadrotor/blender.xml b/conf/airframes/ENAC/quadrotor/blender.xml index 4a23ddd7b6..c1682f0477 100644 --- a/conf/airframes/ENAC/quadrotor/blender.xml +++ b/conf/airframes/ENAC/quadrotor/blender.xml @@ -228,7 +228,6 @@
-
diff --git a/conf/airframes/ENAC/quadrotor/booz2_g1.xml b/conf/airframes/ENAC/quadrotor/booz2_g1.xml index db0e515bc6..345cdd9621 100644 --- a/conf/airframes/ENAC/quadrotor/booz2_g1.xml +++ b/conf/airframes/ENAC/quadrotor/booz2_g1.xml @@ -193,9 +193,7 @@
- -
diff --git a/conf/airframes/ENAC/quadrotor/g1_vision.xml b/conf/airframes/ENAC/quadrotor/g1_vision.xml index 001a712d4e..521d7c87ce 100644 --- a/conf/airframes/ENAC/quadrotor/g1_vision.xml +++ b/conf/airframes/ENAC/quadrotor/g1_vision.xml @@ -174,9 +174,7 @@
- -
diff --git a/conf/airframes/ENAC/quadrotor/mkk1-vision.xml b/conf/airframes/ENAC/quadrotor/mkk1-vision.xml index b81cb8ac65..03f539783f 100644 --- a/conf/airframes/ENAC/quadrotor/mkk1-vision.xml +++ b/conf/airframes/ENAC/quadrotor/mkk1-vision.xml @@ -207,9 +207,7 @@
- -
diff --git a/conf/airframes/ENAC/quadrotor/mkk1.xml b/conf/airframes/ENAC/quadrotor/mkk1.xml index c44af4ea1c..ee3afbe1c7 100644 --- a/conf/airframes/ENAC/quadrotor/mkk1.xml +++ b/conf/airframes/ENAC/quadrotor/mkk1.xml @@ -227,9 +227,7 @@
- -
diff --git a/conf/airframes/ENAC/quadrotor/nova1.xml b/conf/airframes/ENAC/quadrotor/nova1.xml index 1d75a0ee58..a3a05aadf2 100644 --- a/conf/airframes/ENAC/quadrotor/nova1.xml +++ b/conf/airframes/ENAC/quadrotor/nova1.xml @@ -198,9 +198,7 @@
- -
diff --git a/conf/airframes/NoVa_L.xml b/conf/airframes/NoVa_L.xml index 4a8f9b0a4c..e4a4e36889 100644 --- a/conf/airframes/NoVa_L.xml +++ b/conf/airframes/NoVa_L.xml @@ -102,9 +102,7 @@
- -
diff --git a/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_asctec_example.xml b/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_asctec_example.xml index 9e05da1098..830c2d2260 100644 --- a/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_asctec_example.xml +++ b/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_asctec_example.xml @@ -178,9 +178,7 @@
- -
diff --git a/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_mkk_example.xml b/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_mkk_example.xml index 7c4c1e8e8a..750ad110ec 100644 --- a/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_mkk_example.xml +++ b/conf/airframes/PPZUAV/quadrotor/ppzuav_booz2_mkk_example.xml @@ -196,9 +196,7 @@
- -
diff --git a/conf/airframes/Poine/booz2_a1.xml b/conf/airframes/Poine/booz2_a1.xml index f90a486d32..30358596c0 100644 --- a/conf/airframes/Poine/booz2_a1.xml +++ b/conf/airframes/Poine/booz2_a1.xml @@ -169,9 +169,7 @@
- -
diff --git a/conf/airframes/Poine/booz2_a1p.xml b/conf/airframes/Poine/booz2_a1p.xml index e0903b41a3..4dc659aa53 100644 --- a/conf/airframes/Poine/booz2_a1p.xml +++ b/conf/airframes/Poine/booz2_a1p.xml @@ -173,9 +173,7 @@
- -
diff --git a/conf/airframes/Poine/booz2_a7.xml b/conf/airframes/Poine/booz2_a7.xml index fe7afd9476..895ac7e33b 100644 --- a/conf/airframes/Poine/booz2_a7.xml +++ b/conf/airframes/Poine/booz2_a7.xml @@ -74,9 +74,7 @@
- -
diff --git a/conf/airframes/Poine/booz2_a8.xml b/conf/airframes/Poine/booz2_a8.xml index 46ad289276..c98fbb24cb 100644 --- a/conf/airframes/Poine/booz2_a8.xml +++ b/conf/airframes/Poine/booz2_a8.xml @@ -182,9 +182,7 @@
- -
diff --git a/conf/airframes/Poine/easy_glider1.xml b/conf/airframes/Poine/easy_glider1.xml index 25b6298d47..44791bc811 100644 --- a/conf/airframes/Poine/easy_glider1.xml +++ b/conf/airframes/Poine/easy_glider1.xml @@ -76,7 +76,6 @@
-
diff --git a/conf/airframes/Poine/h_hex.xml b/conf/airframes/Poine/h_hex.xml index db9214e262..44d7782f14 100644 --- a/conf/airframes/Poine/h_hex.xml +++ b/conf/airframes/Poine/h_hex.xml @@ -76,9 +76,7 @@
- -
diff --git a/conf/airframes/UofAdelaide/A1000_BOOZ.xml b/conf/airframes/UofAdelaide/A1000_BOOZ.xml index 54dbc672ca..1a5c088e1c 100644 --- a/conf/airframes/UofAdelaide/A1000_BOOZ.xml +++ b/conf/airframes/UofAdelaide/A1000_BOOZ.xml @@ -242,9 +242,7 @@ second attempt
- -
diff --git a/conf/airframes/UofAdelaide/A1000_LISA.xml b/conf/airframes/UofAdelaide/A1000_LISA.xml index 5493c8d8c5..f48128a609 100644 --- a/conf/airframes/UofAdelaide/A1000_LISA.xml +++ b/conf/airframes/UofAdelaide/A1000_LISA.xml @@ -74,9 +74,7 @@
- -
diff --git a/conf/airframes/UofAdelaide/A1000_NOVA.xml b/conf/airframes/UofAdelaide/A1000_NOVA.xml index 761350b2c9..bcef6ccc71 100644 --- a/conf/airframes/UofAdelaide/A1000_NOVA.xml +++ b/conf/airframes/UofAdelaide/A1000_NOVA.xml @@ -204,10 +204,7 @@
- - -
diff --git a/conf/airframes/UofAdelaide/booz2_NoVa_001_1000.xml b/conf/airframes/UofAdelaide/booz2_NoVa_001_1000.xml index e2189844cc..e00eac3141 100644 --- a/conf/airframes/UofAdelaide/booz2_NoVa_001_1000.xml +++ b/conf/airframes/UofAdelaide/booz2_NoVa_001_1000.xml @@ -204,10 +204,7 @@
- - -
diff --git a/conf/airframes/UofAdelaide/booz2_a1000.xml b/conf/airframes/UofAdelaide/booz2_a1000.xml index bc0f5c553a..3ea1b957b4 100755 --- a/conf/airframes/UofAdelaide/booz2_a1000.xml +++ b/conf/airframes/UofAdelaide/booz2_a1000.xml @@ -244,9 +244,7 @@ second attempt
- -
diff --git a/conf/airframes/UofAdelaide/lisa_a1000.xml b/conf/airframes/UofAdelaide/lisa_a1000.xml index 71ddb6413d..bf9899187e 100644 --- a/conf/airframes/UofAdelaide/lisa_a1000.xml +++ b/conf/airframes/UofAdelaide/lisa_a1000.xml @@ -71,9 +71,7 @@
- -
diff --git a/conf/airframes/booz2_flixr.xml b/conf/airframes/booz2_flixr.xml index 6aa4a7ee6d..f21e10ec05 100644 --- a/conf/airframes/booz2_flixr.xml +++ b/conf/airframes/booz2_flixr.xml @@ -212,7 +212,6 @@
- diff --git a/conf/airframes/booz2_ppzuav.xml b/conf/airframes/booz2_ppzuav.xml index 0961e3f73f..2078e7e7de 100644 --- a/conf/airframes/booz2_ppzuav.xml +++ b/conf/airframes/booz2_ppzuav.xml @@ -179,10 +179,7 @@
- - -
diff --git a/conf/airframes/easy_glider_example.xml b/conf/airframes/easy_glider_example.xml index 4981d5fb8f..9bbb174eab 100644 --- a/conf/airframes/easy_glider_example.xml +++ b/conf/airframes/easy_glider_example.xml @@ -69,7 +69,6 @@
-
diff --git a/conf/airframes/esden/jt_lisam.xml b/conf/airframes/esden/jt_lisam.xml index cd1948f709..2634c9c3f1 100644 --- a/conf/airframes/esden/jt_lisam.xml +++ b/conf/airframes/esden/jt_lisam.xml @@ -65,9 +65,7 @@
- -
diff --git a/conf/airframes/esden/lisa_asctec.xml b/conf/airframes/esden/lisa_asctec.xml index b2a8c41b02..50c0a66790 100644 --- a/conf/airframes/esden/lisa_asctec.xml +++ b/conf/airframes/esden/lisa_asctec.xml @@ -81,9 +81,7 @@
- -
diff --git a/conf/airframes/esden/lisa_asctec_aspirin.xml b/conf/airframes/esden/lisa_asctec_aspirin.xml index 67bad41320..66ff357bd1 100644 --- a/conf/airframes/esden/lisa_asctec_aspirin.xml +++ b/conf/airframes/esden/lisa_asctec_aspirin.xml @@ -81,9 +81,7 @@
- -
diff --git a/conf/airframes/esden/lisa_m_pwm.xml b/conf/airframes/esden/lisa_m_pwm.xml index c7aa63004b..57a8443969 100644 --- a/conf/airframes/esden/lisa_m_pwm.xml +++ b/conf/airframes/esden/lisa_m_pwm.xml @@ -95,9 +95,7 @@
- -
diff --git a/conf/airframes/esden/lisa_pwm_aspirin.xml b/conf/airframes/esden/lisa_pwm_aspirin.xml index 86ecf78dd6..2a6bea0249 100644 --- a/conf/airframes/esden/lisa_pwm_aspirin.xml +++ b/conf/airframes/esden/lisa_pwm_aspirin.xml @@ -69,9 +69,7 @@
- -
diff --git a/conf/airframes/esden/synerani_4B.xml b/conf/airframes/esden/synerani_4B.xml index 7b6827b926..acf1337d7d 100644 --- a/conf/airframes/esden/synerani_4B.xml +++ b/conf/airframes/esden/synerani_4B.xml @@ -72,9 +72,7 @@
- -
diff --git a/conf/airframes/mm/extra/rctx.xml b/conf/airframes/mm/extra/rctx.xml index da6e0d221f..ad468276c0 100644 --- a/conf/airframes/mm/extra/rctx.xml +++ b/conf/airframes/mm/extra/rctx.xml @@ -12,7 +12,6 @@
- diff --git a/conf/airframes/mm/fixed-wing/funjetgfi3.xml b/conf/airframes/mm/fixed-wing/funjetgfi3.xml index 4570d819b7..b90be3eb3b 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi3.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi3.xml @@ -79,7 +79,6 @@
- diff --git a/conf/airframes/mm/fixed-wing/funjetgfi4.xml b/conf/airframes/mm/fixed-wing/funjetgfi4.xml index 4b2a1a8d56..e7326bcfe3 100644 --- a/conf/airframes/mm/fixed-wing/funjetgfi4.xml +++ b/conf/airframes/mm/fixed-wing/funjetgfi4.xml @@ -78,7 +78,6 @@
- diff --git a/conf/airframes/mm/hangar/black_one.xml b/conf/airframes/mm/hangar/black_one.xml index be9796bf51..d7e6d06287 100644 --- a/conf/airframes/mm/hangar/black_one.xml +++ b/conf/airframes/mm/hangar/black_one.xml @@ -103,7 +103,6 @@
- diff --git a/conf/airframes/mm/hangar/glass_one1.xml b/conf/airframes/mm/hangar/glass_one1.xml index e8bf7ff754..82b92dedd8 100644 --- a/conf/airframes/mm/hangar/glass_one1.xml +++ b/conf/airframes/mm/hangar/glass_one1.xml @@ -91,7 +91,6 @@
- diff --git a/conf/airframes/mm/hangar/glass_one2.xml b/conf/airframes/mm/hangar/glass_one2.xml index 2aa4cd4511..3848eadc40 100644 --- a/conf/airframes/mm/hangar/glass_one2.xml +++ b/conf/airframes/mm/hangar/glass_one2.xml @@ -74,7 +74,6 @@
- diff --git a/conf/airframes/mm/hangar/glass_one3.xml b/conf/airframes/mm/hangar/glass_one3.xml index 64c7c610fb..834100ad89 100644 --- a/conf/airframes/mm/hangar/glass_one3.xml +++ b/conf/airframes/mm/hangar/glass_one3.xml @@ -92,7 +92,6 @@
- diff --git a/conf/airframes/mm/hangar/mac06a.xml b/conf/airframes/mm/hangar/mac06a.xml index 932014cd75..63dae8793b 100644 --- a/conf/airframes/mm/hangar/mac06a.xml +++ b/conf/airframes/mm/hangar/mac06a.xml @@ -89,7 +89,6 @@
- diff --git a/conf/airframes/mm/hangar/red_one.xml b/conf/airframes/mm/hangar/red_one.xml index 887601c421..2c074fcba9 100644 --- a/conf/airframes/mm/hangar/red_one.xml +++ b/conf/airframes/mm/hangar/red_one.xml @@ -96,7 +96,6 @@
- diff --git a/conf/airframes/mm/rotor/qmk1.xml b/conf/airframes/mm/rotor/qmk1.xml index a210004acd..c414b3214b 100644 --- a/conf/airframes/mm/rotor/qmk1.xml +++ b/conf/airframes/mm/rotor/qmk1.xml @@ -81,9 +81,7 @@
- -
From 9c36a79c8dbdac837ba2a672f086b75014ff88ea Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 17:47:22 +0100 Subject: [PATCH 024/112] print an error if IR_HORIZ_SENSOR_[ALIGNED|TILTED] is not defined --- sw/airborne/subsystems/sensors/infrared.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/subsystems/sensors/infrared.h b/sw/airborne/subsystems/sensors/infrared.h index 4b5e0e4acc..389fb4314b 100644 --- a/sw/airborne/subsystems/sensors/infrared.h +++ b/sw/airborne/subsystems/sensors/infrared.h @@ -54,6 +54,8 @@ */ #define IR_RollOfIrs(_ir1, _ir2) (_ir1 + _ir2) #define IR_PitchOfIrs(_ir1, _ir2) (-(_ir1) + _ir2) +#else +#error "You have to define either HORIZ_SENSOR_ALIGNED or HORIZ_SENSOR_TILTED in the IR section" #endif /* Vertical sensor, TOP_SIGN gives positice values when it's warm on the bottom */ #ifndef IR_TopOfIr From 22a3b9496d06fbb3b2747316c8490608d0f4e867 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 19:18:38 +0100 Subject: [PATCH 025/112] fix sitl with stupid ir simulation --- sw/airborne/arch/sim/sim_ap.c | 1 - sw/airborne/subsystems/sensors/infrared.h | 2 ++ 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/sw/airborne/arch/sim/sim_ap.c b/sw/airborne/arch/sim/sim_ap.c index a37a453baa..c5e1a652db 100644 --- a/sw/airborne/arch/sim/sim_ap.c +++ b/sw/airborne/arch/sim/sim_ap.c @@ -17,7 +17,6 @@ #include "subsystems/nav.h" #include "firmwares/fixedwing/stabilization/stabilization_attitude.h" #include "firmwares/fixedwing/guidance/guidance_v.h" -#include "subsystems/sensors/infrared.h" #include "commands.h" #include "firmwares/fixedwing/main_ap.h" #include "ap_downlink.h" diff --git a/sw/airborne/subsystems/sensors/infrared.h b/sw/airborne/subsystems/sensors/infrared.h index 389fb4314b..84ad3ac4e3 100644 --- a/sw/airborne/subsystems/sensors/infrared.h +++ b/sw/airborne/subsystems/sensors/infrared.h @@ -55,8 +55,10 @@ #define IR_RollOfIrs(_ir1, _ir2) (_ir1 + _ir2) #define IR_PitchOfIrs(_ir1, _ir2) (-(_ir1) + _ir2) #else +#ifndef SITL #error "You have to define either HORIZ_SENSOR_ALIGNED or HORIZ_SENSOR_TILTED in the IR section" #endif +#endif /* Vertical sensor, TOP_SIGN gives positice values when it's warm on the bottom */ #ifndef IR_TopOfIr #define IR_TopOfIr(_ir) (_ir) From 12e547c8d60e8345a2f0ba4e6b7e63bcacebd579 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 24 Nov 2011 23:49:16 +0100 Subject: [PATCH 026/112] get rid of unused arg warning in sim_gps --- sw/airborne/arch/sim/sim_gps.c | 1 + 1 file changed, 1 insertion(+) diff --git a/sw/airborne/arch/sim/sim_gps.c b/sw/airborne/arch/sim/sim_gps.c index 0930c39f34..13ef9b84cd 100644 --- a/sw/airborne/arch/sim/sim_gps.c +++ b/sw/airborne/arch/sim/sim_gps.c @@ -47,6 +47,7 @@ value sim_use_gps_pos(value x, value y, value z, value c, value a, value s, valu gps.utm_pos.north = Int_val(y); gps.utm_pos.zone = Int_val(z); lat = lon; /* Just to get rid of the "unused arg" warning */ + lon = lat; /* Just to get rid of the "unused arg" warning */ #endif // GPS_USE_LATLONG From 87096f5340ef41e3e871cb7e61b1c5fb2c7b4f87 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 25 Nov 2011 22:59:53 +0100 Subject: [PATCH 027/112] try to fix gc-sections for stm32, error before was arm-none-eabi-gcc: error: unrecognized option '--gc-sections' --- conf/Makefile.stm32 | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/conf/Makefile.stm32 b/conf/Makefile.stm32 index 707d867861..edd19a7e1f 100644 --- a/conf/Makefile.stm32 +++ b/conf/Makefile.stm32 @@ -118,7 +118,7 @@ endif MULTILIB = $(shell if $(CC) --print-multi-lib | grep thumb2 > /dev/null ; then echo "yes"; else echo "no"; fi) CFLAGS = -I. -I./$(ARCH) $(INCLUDES) -D__thumb2__ -Wall -msoft-float -O$(OPT) -CFLAGS += -Wl,gc-sections +CFLAGS += -Wl,--gc-sections CFLAGS += -mcpu=$(MCU) -mthumb -ansi ifeq ("$(MULTILIB)","yes") CFLAGS += -mfix-cortex-m3-ldrd @@ -149,9 +149,9 @@ endif AFLAGS += -x assembler-with-cpp -Wa,-adhlns=$(OBJDIR)/$(<:.S=.lst),--g$(DEBUG) ifeq ("$(MULTILIB)","yes") -LDFLAGS = -T$(LDSCRIPT) -nostartfiles -O$(OPT) --gc-sections -mthumb -march=armv7 -mfix-cortex-m3-ldrd -msoft-float +LDFLAGS = -T$(LDSCRIPT) -nostartfiles -O$(OPT) -mthumb -march=armv7 -mfix-cortex-m3-ldrd -msoft-float else -LDFLAGS = -D__thumb2__ -T$(LDSCRIPT) -nostartfiles -L$(GCC_LIB_DIR) -O$(OPT) --gc-sections +LDFLAGS = -D__thumb2__ -T$(LDSCRIPT) -nostartfiles -L$(GCC_LIB_DIR) -O$(OPT) endif LDFLAGS += -Wl,-Map=$(OBJDIR)/$(TARGET).map,--cref,--gc-sections LDLIBS += -lc -lm -lgcc -lcmsis -lstm32 -l$(LIBOPENCM3_LIB) From 4af98cff08b0312e4615c48acde43bc85118da7c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 27 Nov 2011 12:53:31 +0100 Subject: [PATCH 028/112] renamed temporary local var nav_init to ecef_nav0, nav_init shadowed global declaration --- sw/airborne/subsystems/ins.c | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/sw/airborne/subsystems/ins.c b/sw/airborne/subsystems/ins.c index d25b367a84..c5b87519bf 100644 --- a/sw/airborne/subsystems/ins.c +++ b/sw/airborne/subsystems/ins.c @@ -91,16 +91,16 @@ void ins_init() { ins_ltp_initialised = TRUE; /** FIXME: should use the same code than MOVE_WP in firmwares/rotorcraft/datalink.c */ - struct LlaCoor_i llh; /* Height above the ellipsoid */ - llh.lat = INT32_RAD_OF_DEG(NAV_LAT0); - llh.lon = INT32_RAD_OF_DEG(NAV_LON0); + struct LlaCoor_i llh_nav0; /* Height above the ellipsoid */ + llh_nav0.lat = INT32_RAD_OF_DEG(NAV_LAT0); + llh_nav0.lon = INT32_RAD_OF_DEG(NAV_LON0); /* NAV_ALT0 = ground alt above msl, NAV_MSL0 = geoid-height (msl) over ellipsoid */ - llh.alt = NAV_ALT0 + NAV_MSL0; + llh_nav0.alt = NAV_ALT0 + NAV_MSL0; - struct EcefCoor_i nav_init; - ecef_of_lla_i(&nav_init, &llh); + struct EcefCoor_i ecef_nav0; + ecef_of_lla_i(&ecef_nav0, &llh_nav0); - ltp_def_from_ecef_i(&ins_ltp_def, &nav_init); + ltp_def_from_ecef_i(&ins_ltp_def, &ecef_nav0); ins_ltp_def.hmsl = NAV_ALT0; #else ins_ltp_initialised = FALSE; From 986142573a3d6712e0ea47c622a33b18a4d39534 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 29 Nov 2011 17:30:39 +0100 Subject: [PATCH 029/112] bound trim values at 10% of max command value --- conf/settings/tuning.xml | 4 ++-- conf/settings/tuning_ins.xml | 4 ++-- sw/airborne/firmwares/fixedwing/main_fbw.c | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/conf/settings/tuning.xml b/conf/settings/tuning.xml index c430c97e34..cf1fcb3f4c 100644 --- a/conf/settings/tuning.xml +++ b/conf/settings/tuning.xml @@ -32,8 +32,8 @@ - - + + diff --git a/conf/settings/tuning_ins.xml b/conf/settings/tuning_ins.xml index 0a5aea0529..0aa57141ef 100644 --- a/conf/settings/tuning_ins.xml +++ b/conf/settings/tuning_ins.xml @@ -32,8 +32,8 @@ - - + + diff --git a/sw/airborne/firmwares/fixedwing/main_fbw.c b/sw/airborne/firmwares/fixedwing/main_fbw.c index e5e2ffc5b5..318126b599 100644 --- a/sw/airborne/firmwares/fixedwing/main_fbw.c +++ b/sw/airborne/firmwares/fixedwing/main_fbw.c @@ -155,10 +155,10 @@ void event_task_fbw( void) { for(i = 0; i < COMMANDS_NB; i++) trimmed_commands[i] = commands[i]; #ifdef COMMAND_ROLL - trimmed_commands[COMMAND_ROLL] += command_roll_trim; + trimmed_commands[COMMAND_ROLL] += ChopAbs(command_roll_trim, MAX_PPRZ/10); #endif #ifdef COMMAND_PITCH - trimmed_commands[COMMAND_PITCH] += command_pitch_trim; + trimmed_commands[COMMAND_PITCH] += ChopAbs(command_pitch_trim, MAX_PPRZ/10); #endif SetActuatorsFromCommands(trimmed_commands); From 033b29c4f6422a8cc9d965451355f1faf82400ef Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 1 Dec 2011 11:59:15 +0100 Subject: [PATCH 030/112] removed a warning about missing default case --- sw/airborne/subsystems/gps/gps_mtk.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/subsystems/gps/gps_mtk.c b/sw/airborne/subsystems/gps/gps_mtk.c index aaa96859e6..79a157db86 100644 --- a/sw/airborne/subsystems/gps/gps_mtk.c +++ b/sw/airborne/subsystems/gps/gps_mtk.c @@ -386,6 +386,8 @@ static bool_t user_gps_configure(bool_t cpt) { case 1: MtkSend_CFG(MTK_DIY_OUTPUT_RATE); return FALSE; + default: + break; } return TRUE; /* Continue, except for the last case */ } From 9329809f53891ab17a7a280e8a6da6a642bd1fed Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 5 Dec 2011 20:23:33 +0100 Subject: [PATCH 031/112] make it possible to set RADIO_CONTROL_LED to none --- conf/autopilot/subsystems/shared/radio_control_ppm.makefile | 2 +- .../autopilot/subsystems/shared/radio_control_spektrum.makefile | 2 +- conf/boards/classix.makefile | 1 + conf/boards/hb_1.1.makefile | 1 + conf/boards/tiny_2.11.makefile | 2 ++ conf/boards/umarim_1.0.makefile | 2 ++ 6 files changed, 8 insertions(+), 2 deletions(-) diff --git a/conf/autopilot/subsystems/shared/radio_control_ppm.makefile b/conf/autopilot/subsystems/shared/radio_control_ppm.makefile index 6b2fdeab88..41b7f90729 100644 --- a/conf/autopilot/subsystems/shared/radio_control_ppm.makefile +++ b/conf/autopilot/subsystems/shared/radio_control_ppm.makefile @@ -12,7 +12,7 @@ endif ifeq ($(NORADIO), False) $(TARGET).CFLAGS += -DRADIO_CONTROL - ifdef RADIO_CONTROL_LED + ifneq ($(RADIO_CONTROL_LED),none) ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) endif $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/ppm.h\" diff --git a/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile b/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile index ae53bd7a26..192a21c376 100644 --- a/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile +++ b/conf/autopilot/subsystems/shared/radio_control_spektrum.makefile @@ -10,7 +10,7 @@ ap.CFLAGS += -DRADIO_CONTROL_TYPE_H=\"subsystems/radio_control/spektrum.h\" ifeq ($(ARCH), lpc21) ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_MODEL_H=$(RADIO_CONTROL_SPEKTRUM_MODEL) endif -ifdef RADIO_CONTROL_LED +ifneq ($(RADIO_CONTROL_LED),none) ap.CFLAGS += -DRADIO_CONTROL_LED=$(RADIO_CONTROL_LED) endif ap.CFLAGS += -DRADIO_CONTROL_SPEKTRUM_PRIMARY_PORT=$(RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT) diff --git a/conf/boards/classix.makefile b/conf/boards/classix.makefile index 79002ad107..055ec54e92 100644 --- a/conf/boards/classix.makefile +++ b/conf/boards/classix.makefile @@ -24,6 +24,7 @@ LPC21ISP_XTAL = 12000 ### default settings for classix GPS_BAUD = B38400 GPS_LED = none +RADIO_CONTROL_LED = none # All targets on the TINY board run on the same processor achitecture $(TARGET).ARCHDIR = $(ARCH) diff --git a/conf/boards/hb_1.1.makefile b/conf/boards/hb_1.1.makefile index b8d0c3ae0a..4c2a8c8525 100644 --- a/conf/boards/hb_1.1.makefile +++ b/conf/boards/hb_1.1.makefile @@ -37,6 +37,7 @@ GPS_BAUD = B38400 endif GPS_LED = 2 +RADIO_CONTROL_LED = none ifndef ADC_IR1 ADC_IR1 = 1 diff --git a/conf/boards/tiny_2.11.makefile b/conf/boards/tiny_2.11.makefile index 33c35ec77c..00cbc94af6 100644 --- a/conf/boards/tiny_2.11.makefile +++ b/conf/boards/tiny_2.11.makefile @@ -36,6 +36,8 @@ ifndef MODEM_BAUD MODEM_BAUD = B57600 endif +RADIO_CONTROL_LED = none + ADC_IR_TOP = ADC_0 ADC_IR1 = ADC_1 ADC_IR2 = ADC_2 diff --git a/conf/boards/umarim_1.0.makefile b/conf/boards/umarim_1.0.makefile index 793cc91778..3ebc16dbcd 100644 --- a/conf/boards/umarim_1.0.makefile +++ b/conf/boards/umarim_1.0.makefile @@ -29,6 +29,8 @@ GPS_BAUD = B38400 endif GPS_LED = 2 +RADIO_CONTROL_LED = none + ifndef MODEM_PORT MODEM_PORT = UART1 endif From fc4c250cb625b360e965cdeba134640b653f7fcb Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 5 Dec 2011 20:39:30 +0100 Subject: [PATCH 032/112] explicitly configure a RADIO_CONTROL_DATALINK_LED if wanted --- .../subsystems/fixedwing/radio_control_datalink.makefile | 3 +++ sw/airborne/firmwares/fixedwing/datalink.c | 8 ++++++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/conf/autopilot/subsystems/fixedwing/radio_control_datalink.makefile b/conf/autopilot/subsystems/fixedwing/radio_control_datalink.makefile index 6202acf1b8..bb342a5c3e 100644 --- a/conf/autopilot/subsystems/fixedwing/radio_control_datalink.makefile +++ b/conf/autopilot/subsystems/fixedwing/radio_control_datalink.makefile @@ -11,6 +11,9 @@ endif ifeq ($(NORADIO), False) +ifdef (RADIO_CONTROL_DATALINK_LED) + ap.CFLAGS += -D(RADIO_CONTROL_DATALINK_LED=$((RADIO_CONTROL_DATALINK_LED) +endif $(TARGET).CFLAGS += -DRADIO_CONTROL $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_H=\"radio_control/rc_datalink.h\" $(TARGET).CFLAGS += -DRADIO_CONTROL_TYPE_DATALINK diff --git a/sw/airborne/firmwares/fixedwing/datalink.c b/sw/airborne/firmwares/fixedwing/datalink.c index 106156e564..bbd43d3eb1 100644 --- a/sw/airborne/firmwares/fixedwing/datalink.c +++ b/sw/airborne/firmwares/fixedwing/datalink.c @@ -187,14 +187,18 @@ void dl_parse_msg(void) { #endif // USE_JOYSTICK #if defined RADIO_CONTROL && defined RADIO_CONTROL_TYPE_DATALINK if (msg_id == DL_RC_3CH /*&& DL_RC_3CH_ac_id(dl_buffer) == TX_ID*/) { -LED_TOGGLE(3); +#ifdef RADIO_CONTROL_DATALINK_LED + LED_TOGGLE(RADIO_CONTROL_DATALINK_LED); +#endif parse_rc_3ch_datalink( DL_RC_3CH_throttle_mode(dl_buffer), DL_RC_3CH_roll(dl_buffer), DL_RC_3CH_pitch(dl_buffer)); } else if (msg_id == DL_RC_4CH && DL_RC_4CH_ac_id(dl_buffer) == AC_ID) { -LED_TOGGLE(3); +#ifdef RADIO_CONTROL_DATALINK_LED + LED_TOGGLE(RADIO_CONTROL_DATALINK_LED); +#endif parse_rc_4ch_datalink( DL_RC_4CH_mode(dl_buffer), DL_RC_4CH_throttle(dl_buffer), From 977bc6debe012a0535580c47242c582a3e679822 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 5 Dec 2011 22:57:58 +0100 Subject: [PATCH 033/112] added trim to a few more tuning files --- conf/settings/tuning_ctl_adaptive.xml | 5 +++++ conf/settings/tuning_ctl_new.xml | 5 +++++ conf/settings/tuning_ins_dcm.xml | 5 +++++ conf/settings/tuning_loiter.xml | 4 ++++ 4 files changed, 19 insertions(+) diff --git a/conf/settings/tuning_ctl_adaptive.xml b/conf/settings/tuning_ctl_adaptive.xml index 7cd558dae2..6271f6aa9c 100644 --- a/conf/settings/tuning_ctl_adaptive.xml +++ b/conf/settings/tuning_ctl_adaptive.xml @@ -6,6 +6,11 @@ + + + + + diff --git a/conf/settings/tuning_ctl_new.xml b/conf/settings/tuning_ctl_new.xml index d283b907fb..38f5e825fe 100644 --- a/conf/settings/tuning_ctl_new.xml +++ b/conf/settings/tuning_ctl_new.xml @@ -6,6 +6,11 @@ + + + + + diff --git a/conf/settings/tuning_ins_dcm.xml b/conf/settings/tuning_ins_dcm.xml index 4ba4f43d96..91b399acbe 100644 --- a/conf/settings/tuning_ins_dcm.xml +++ b/conf/settings/tuning_ins_dcm.xml @@ -31,6 +31,11 @@ + + + + + diff --git a/conf/settings/tuning_loiter.xml b/conf/settings/tuning_loiter.xml index eb6a88c2fe..823fd33523 100644 --- a/conf/settings/tuning_loiter.xml +++ b/conf/settings/tuning_loiter.xml @@ -44,6 +44,10 @@ + + + + From 97977aad0e2231f02d0300399d297402843e8749 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 5 Dec 2011 23:07:50 +0100 Subject: [PATCH 034/112] fix detection of new libopencm3 layout for settings_arch --- sw/airborne/arch/stm32/subsystems/settings_arch.c | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/sw/airborne/arch/stm32/subsystems/settings_arch.c b/sw/airborne/arch/stm32/subsystems/settings_arch.c index 38e1bcd7a8..9ac5d761aa 100644 --- a/sw/airborne/arch/stm32/subsystems/settings_arch.c +++ b/sw/airborne/arch/stm32/subsystems/settings_arch.c @@ -35,9 +35,14 @@ #include "subsystems/settings.h" -#include +#if defined(STM32F1) || defined(STM32F2) || defined(STM32F4) +#include +#include +#else #include #include +#endif +#include struct FlashInfo { uint32_t addr; From 6f9fcc2cc0331a7be3d181cc7fa317be15ffa82c Mon Sep 17 00:00:00 2001 From: lamestllama Date: Tue, 6 Dec 2011 23:10:11 +1030 Subject: [PATCH 035/112] alignment of FGNetGUI struct fixed for 64 bit linux and 32 bit Flightgear on OSX --- sw/simulator/flight_gear.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/sw/simulator/flight_gear.h b/sw/simulator/flight_gear.h index b5515c89cb..0faf8111a4 100644 --- a/sw/simulator/flight_gear.h +++ b/sw/simulator/flight_gear.h @@ -211,7 +211,9 @@ struct FGNetMiniFDM { #define FG_NET_GUI_VERSION 7 #define FG_NET_GUI_MAX_TANKS 4 -#ifdef __x86_64__ +// FIXME: Flightgear on OSX is still 32 bit get rid +// off these pragmas when it goes to 64 bit. +#ifdef __x86_64__ && __APPLE__ #pragma pack(push) #pragma pack(4) #endif @@ -249,7 +251,7 @@ struct FGNetGUI { float course_deviation_deg; // degrees off target course float gs_deviation_deg; // degrees off target glide slope }; -#ifdef __x86_64__ +#ifdef __x86_64__ && __APPLE__ #pragma pack(push) #pragma pack(pop) #endif From dfc1675a5473c8ae149ab0a58a8297e6f7d5e1f8 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 6 Dec 2011 15:47:42 +0100 Subject: [PATCH 036/112] trying to get this working on linux 64bit and fg 64bit --- sw/simulator/flight_gear.h | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/sw/simulator/flight_gear.h b/sw/simulator/flight_gear.h index 0faf8111a4..eaf35b0ea9 100644 --- a/sw/simulator/flight_gear.h +++ b/sw/simulator/flight_gear.h @@ -211,11 +211,15 @@ struct FGNetMiniFDM { #define FG_NET_GUI_VERSION 7 #define FG_NET_GUI_MAX_TANKS 4 -// FIXME: Flightgear on OSX is still 32 bit get rid +// FIXME: Flightgear on OSX is still 32 bit get rid // off these pragmas when it goes to 64 bit. -#ifdef __x86_64__ && __APPLE__ +#ifdef __x86_64__ #pragma pack(push) +#ifdef __APPLE__ #pragma pack(4) +#else +#pragma pack(8) +#endif #endif struct FGNetGUI { uint32_t version; // increment when data values change @@ -251,7 +255,7 @@ struct FGNetGUI { float course_deviation_deg; // degrees off target course float gs_deviation_deg; // degrees off target glide slope }; -#ifdef __x86_64__ && __APPLE__ +#ifdef __x86_64__ #pragma pack(push) #pragma pack(pop) #endif From 3269a1f7c7c62ae2abe175e8b708f762c16730b3 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 6 Dec 2011 19:22:18 +0100 Subject: [PATCH 037/112] added comment to actuators_mkk makefile about I2C_TRANSACTION_QUEUE_LEN --- conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile | 2 ++ 1 file changed, 2 insertions(+) diff --git a/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile b/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile index 5922e9c2ce..ed4da826d6 100644 --- a/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile +++ b/conf/autopilot/subsystems/rotorcraft/actuators_mkk.makefile @@ -6,6 +6,8 @@ # ... # # +# +# #
# # From bc8e4e7bcf2835548323990074157eff754e0fb1 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 6 Dec 2011 19:39:56 +0100 Subject: [PATCH 038/112] added subsystem makefiles for aspirin v1.0 and v1.5 See github issue #96 and plese report other channel/sign problems with other aspirin versions. Please replace with (or aspirin_v1.5) in your airframe file. --- .../subsystems/shared/imu_aspirin.makefile | 67 +------------------ .../shared/imu_aspirin_common.makefile | 58 ++++++++++++++++ .../shared/imu_aspirin_v1.0.makefile | 46 +++++++++++++ .../shared/imu_aspirin_v1.5.makefile | 46 +++++++++++++ sw/airborne/subsystems/imu/imu_aspirin.h | 23 +++++-- 5 files changed, 170 insertions(+), 70 deletions(-) create mode 100644 conf/autopilot/subsystems/shared/imu_aspirin_common.makefile create mode 100644 conf/autopilot/subsystems/shared/imu_aspirin_v1.0.makefile create mode 100644 conf/autopilot/subsystems/shared/imu_aspirin_v1.5.makefile diff --git a/conf/autopilot/subsystems/shared/imu_aspirin.makefile b/conf/autopilot/subsystems/shared/imu_aspirin.makefile index 51bbaa33e3..1c08dca87b 100644 --- a/conf/autopilot/subsystems/shared/imu_aspirin.makefile +++ b/conf/autopilot/subsystems/shared/imu_aspirin.makefile @@ -1,66 +1,3 @@ -# -# Aspirin IMU -# -# -# required xml: -#
-# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -# -#
-# -# +include $(CFG_SHARED)/imu_aspirin_v1.0.makefile -# imu aspirin - -IMU_ASPIRIN_CFLAGS = -DUSE_IMU -IMU_ASPIRIN_CFLAGS += -DIMU_TYPE_H=\"imu/imu_aspirin.h\" -DIMU_OVERRIDE_CHANNELS -IMU_ASPIRIN_SRCS = $(SRC_SUBSYSTEMS)/imu.c \ - $(SRC_SUBSYSTEMS)/imu/imu_aspirin.c \ - $(SRC_ARCH)/subsystems/imu/imu_aspirin_arch.c - -# Magnetometer -IMU_ASPIRIN_SRCS += peripherals/hmc5843.c $(SRC_ARCH)/peripherals/hmc5843_arch.c - -IMU_ASPIRIN_CFLAGS += -DUSE_I2C2 - -ifeq ($(ARCH), lpc21) -#TODO -else ifeq ($(ARCH), stm32) -IMU_ASPIRIN_CFLAGS += -DUSE_EXTI15_10_IRQ # Gyro Int on PC14 -IMU_ASPIRIN_CFLAGS += -DUSE_EXTI9_5_IRQ # Mag Int on PB5 -IMU_ASPIRIN_CFLAGS += -DUSE_EXTI2_IRQ # Accel Int on PD2 -IMU_ASPIRIN_CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA -endif - - -# Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets -# see: conf/autopilot/subsystems/lisa_passthrough/imu_b2_v1.1.makefile for example -ap.CFLAGS += $(IMU_ASPIRIN_CFLAGS) -ap.srcs += $(IMU_ASPIRIN_SRCS) - -# sim not done yet -#sim.CFLAGS += $(IMU_ASPIRIN_CFLAGS) -#sim.srcs += $(IMU_ASPIRIN_SRCS) +$(warning The imu_aspirin subsystem has been split up into different versions, please replace with (or aspirin_v1.5) in your airframe file.) diff --git a/conf/autopilot/subsystems/shared/imu_aspirin_common.makefile b/conf/autopilot/subsystems/shared/imu_aspirin_common.makefile new file mode 100644 index 0000000000..0deb8e75b3 --- /dev/null +++ b/conf/autopilot/subsystems/shared/imu_aspirin_common.makefile @@ -0,0 +1,58 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# Common part for all Aspirin IMUs +# +# +# required xml: +#
+# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +#
+# +# + +# imu aspirin + +IMU_ASPIRIN_CFLAGS = -DUSE_IMU +IMU_ASPIRIN_CFLAGS += -DIMU_TYPE_H=\"imu/imu_aspirin.h\" -DIMU_OVERRIDE_CHANNELS +IMU_ASPIRIN_SRCS = $(SRC_SUBSYSTEMS)/imu.c \ + $(SRC_SUBSYSTEMS)/imu/imu_aspirin.c \ + $(SRC_ARCH)/subsystems/imu/imu_aspirin_arch.c + +# Magnetometer +IMU_ASPIRIN_SRCS += peripherals/hmc5843.c $(SRC_ARCH)/peripherals/hmc5843_arch.c + +IMU_ASPIRIN_CFLAGS += -DUSE_I2C2 + +ifeq ($(ARCH), lpc21) +#TODO +else ifeq ($(ARCH), stm32) +IMU_ASPIRIN_CFLAGS += -DUSE_EXTI15_10_IRQ # Gyro Int on PC14 +IMU_ASPIRIN_CFLAGS += -DUSE_EXTI9_5_IRQ # Mag Int on PB5 +IMU_ASPIRIN_CFLAGS += -DUSE_EXTI2_IRQ # Accel Int on PD2 +IMU_ASPIRIN_CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA +endif + diff --git a/conf/autopilot/subsystems/shared/imu_aspirin_v1.0.makefile b/conf/autopilot/subsystems/shared/imu_aspirin_v1.0.makefile new file mode 100644 index 0000000000..3e2e8a7c26 --- /dev/null +++ b/conf/autopilot/subsystems/shared/imu_aspirin_v1.0.makefile @@ -0,0 +1,46 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# Aspirin IMU v1.0 +# +# +# required xml: +#
+# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +#
+# +# + +# imu aspirin + +include $(CFG_SHARED)/imu_aspirin_common.makefile + +IMU_ASPIRIN_CFLAGS += -DIMU_ASPIRIN_VERSION_1_0 + +# Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets +# see: conf/autopilot/subsystems/lisa_passthrough/imu_b2_v1.1.makefile for example +ap.CFLAGS += $(IMU_ASPIRIN_CFLAGS) +ap.srcs += $(IMU_ASPIRIN_SRCS) diff --git a/conf/autopilot/subsystems/shared/imu_aspirin_v1.5.makefile b/conf/autopilot/subsystems/shared/imu_aspirin_v1.5.makefile new file mode 100644 index 0000000000..2686e94905 --- /dev/null +++ b/conf/autopilot/subsystems/shared/imu_aspirin_v1.5.makefile @@ -0,0 +1,46 @@ +# Hey Emacs, this is a -*- makefile -*- +# +# Aspirin IMU v1.5 +# +# +# required xml: +#
+# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +#
+# +# + +# imu aspirin + +include $(CFG_SHARED)/imu_aspirin_common.makefile + +IMU_ASPIRIN_CFLAGS += -DIMU_ASPIRIN_VERSION_1_5 + +# Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets +# see: conf/autopilot/subsystems/lisa_passthrough/imu_b2_v1.1.makefile for example +ap.CFLAGS += $(IMU_ASPIRIN_CFLAGS) +ap.srcs += $(IMU_ASPIRIN_SRCS) diff --git a/sw/airborne/subsystems/imu/imu_aspirin.h b/sw/airborne/subsystems/imu/imu_aspirin.h index f14a8f0bc7..39f8e5cd89 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin.h +++ b/sw/airborne/subsystems/imu/imu_aspirin.h @@ -32,9 +32,27 @@ #include "peripherals/hmc5843.h" #include "peripherals/adxl345.h" +#ifdef IMU_ASPIRIN_VERSION_1_0 #define IMU_MAG_X_CHAN 0 #define IMU_MAG_Y_CHAN 1 #define IMU_MAG_Z_CHAN 2 +#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN +#define IMU_MAG_X_SIGN 1 +#define IMU_MAG_Y_SIGN 1 +#define IMU_MAG_Z_SIGN 1 +#endif +#endif + +#ifdef IMU_ASPIRIN_VERSION_1_5 +#define IMU_MAG_X_CHAN 2 +#define IMU_MAG_Y_CHAN 0 +#define IMU_MAG_Z_CHAN 1 +#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN +#define IMU_MAG_X_SIGN 1 +#define IMU_MAG_Y_SIGN -1 +#define IMU_MAG_Z_SIGN 1 +#endif +#endif #if !defined IMU_GYRO_P_SIGN & !defined IMU_GYRO_Q_SIGN & !defined IMU_GYRO_R_SIGN #define IMU_GYRO_P_SIGN 1 @@ -46,11 +64,6 @@ #define IMU_ACCEL_Y_SIGN 1 #define IMU_ACCEL_Z_SIGN 1 #endif -#if !defined IMU_MAG_X_SIGN & !defined IMU_MAG_Y_SIGN & !defined IMU_MAG_Z_SIGN -#define IMU_MAG_X_SIGN 1 -#define IMU_MAG_Y_SIGN 1 -#define IMU_MAG_Z_SIGN 1 -#endif enum AspirinStatus { AspirinStatusUninit, From 8cf2767d390947b56c03e93faea09c6650b607a0 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 7 Dec 2011 03:24:57 +0100 Subject: [PATCH 039/112] fix RADIO_CONTROL_LED for lisa/m --- conf/boards/lisa_m_1.0.makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/conf/boards/lisa_m_1.0.makefile b/conf/boards/lisa_m_1.0.makefile index 0a05903f17..269bc8aef4 100644 --- a/conf/boards/lisa_m_1.0.makefile +++ b/conf/boards/lisa_m_1.0.makefile @@ -31,7 +31,7 @@ SYS_TIME_LED = 1 RADIO_CONTROL_SPEKTRUM_PRIMARY_PORT = UART3 RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT = UART5 -#RADIO_CONTROL_LED = 5 +RADIO_CONTROL_LED = none ifndef MODEM_PORT MODEM_PORT=UART2 From c74786d675d025d6dba6d13846a4759dae291be4 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Wed, 7 Dec 2011 11:41:00 +0100 Subject: [PATCH 040/112] move anemotaxis and chemotaxis navigation routines to enose module --- sw/airborne/{ => modules/enose}/anemotaxis.c | 4 ++-- sw/airborne/{ => modules/enose}/anemotaxis.h | 0 sw/airborne/{ => modules/enose}/chemotaxis.c | 4 ++-- sw/airborne/{ => modules/enose}/chemotaxis.h | 0 4 files changed, 4 insertions(+), 4 deletions(-) rename sw/airborne/{ => modules/enose}/anemotaxis.c (97%) rename sw/airborne/{ => modules/enose}/anemotaxis.h (100%) rename sw/airborne/{ => modules/enose}/chemotaxis.c (94%) rename sw/airborne/{ => modules/enose}/chemotaxis.h (100%) diff --git a/sw/airborne/anemotaxis.c b/sw/airborne/modules/enose/anemotaxis.c similarity index 97% rename from sw/airborne/anemotaxis.c rename to sw/airborne/modules/enose/anemotaxis.c index 562b02b7e1..055816bb84 100644 --- a/sw/airborne/anemotaxis.c +++ b/sw/airborne/modules/enose/anemotaxis.c @@ -1,11 +1,11 @@ -#include "anemotaxis.h" +#include "modules/enose/anemotaxis.h" #include "generated/airframe.h" #include "estimator.h" #include "std.h" #include "subsystems/nav.h" #include "generated/flight_plan.h" #include "ap_downlink.h" -#include "chemo_detect.h" +#include "modules/enose/chemo_detect.h" enum status { UTURN, CROSSWIND }; static enum status status; diff --git a/sw/airborne/anemotaxis.h b/sw/airborne/modules/enose/anemotaxis.h similarity index 100% rename from sw/airborne/anemotaxis.h rename to sw/airborne/modules/enose/anemotaxis.h diff --git a/sw/airborne/chemotaxis.c b/sw/airborne/modules/enose/chemotaxis.c similarity index 94% rename from sw/airborne/chemotaxis.c rename to sw/airborne/modules/enose/chemotaxis.c index 6bc9514c92..bbb6504da2 100644 --- a/sw/airborne/chemotaxis.c +++ b/sw/airborne/modules/enose/chemotaxis.c @@ -1,11 +1,11 @@ -#include "chemotaxis.h" +#include "modules/enose/chemotaxis.h" #include "generated/airframe.h" #include "estimator.h" #include "std.h" #include "subsystems/nav.h" #include "generated/flight_plan.h" #include "ap_downlink.h" -#include "chemo_detect.h" +#include "modules/enose/chemo_detect.h" #define MAX_RADIUS 250 #define ALPHA 0.5 diff --git a/sw/airborne/chemotaxis.h b/sw/airborne/modules/enose/chemotaxis.h similarity index 100% rename from sw/airborne/chemotaxis.h rename to sw/airborne/modules/enose/chemotaxis.h From 217f13a8029d0d97c2500278b59e537a1f33669b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 11 Dec 2011 19:58:54 +0100 Subject: [PATCH 041/112] replaced aspirin imu subsystem with aspirin_v1.0 in airframes files --- conf/airframes/Poine/h_hex.xml | 2 +- conf/airframes/esden/jt_lisam.xml | 2 +- conf/airframes/esden/lisa_asctec_aspirin.xml | 2 +- conf/airframes/esden/lisa_m_pwm.xml | 2 +- conf/airframes/esden/lisa_pwm_aspirin.xml | 2 +- conf/airframes/esden/synerani_4B.xml | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/conf/airframes/Poine/h_hex.xml b/conf/airframes/Poine/h_hex.xml index 44d7782f14..3979fb654c 100644 --- a/conf/airframes/Poine/h_hex.xml +++ b/conf/airframes/Poine/h_hex.xml @@ -181,7 +181,7 @@ - + diff --git a/conf/airframes/esden/jt_lisam.xml b/conf/airframes/esden/jt_lisam.xml index 2634c9c3f1..cb1e3fc21a 100644 --- a/conf/airframes/esden/jt_lisam.xml +++ b/conf/airframes/esden/jt_lisam.xml @@ -194,7 +194,7 @@ - + diff --git a/conf/airframes/esden/lisa_asctec_aspirin.xml b/conf/airframes/esden/lisa_asctec_aspirin.xml index 66ff357bd1..9852a28db6 100644 --- a/conf/airframes/esden/lisa_asctec_aspirin.xml +++ b/conf/airframes/esden/lisa_asctec_aspirin.xml @@ -200,7 +200,7 @@ - + diff --git a/conf/airframes/esden/lisa_m_pwm.xml b/conf/airframes/esden/lisa_m_pwm.xml index 57a8443969..96940571fe 100644 --- a/conf/airframes/esden/lisa_m_pwm.xml +++ b/conf/airframes/esden/lisa_m_pwm.xml @@ -221,7 +221,7 @@ - + diff --git a/conf/airframes/esden/lisa_pwm_aspirin.xml b/conf/airframes/esden/lisa_pwm_aspirin.xml index 2a6bea0249..dd2c46b85e 100644 --- a/conf/airframes/esden/lisa_pwm_aspirin.xml +++ b/conf/airframes/esden/lisa_pwm_aspirin.xml @@ -198,7 +198,7 @@ - + diff --git a/conf/airframes/esden/synerani_4B.xml b/conf/airframes/esden/synerani_4B.xml index acf1337d7d..d96d36b2f0 100644 --- a/conf/airframes/esden/synerani_4B.xml +++ b/conf/airframes/esden/synerani_4B.xml @@ -201,7 +201,7 @@ - + From 46da1d82689d6565f0099a559577014e78ba35f1 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 15 Dec 2011 19:14:31 +0100 Subject: [PATCH 042/112] imu_b2_1.2 is now using hmc58xx driver without interrupts on lpc21 previous driver was not working at all (board frozen) --- .../subsystems/rotorcraft/imu_b2_v1.2.makefile | 12 ++++++------ .../arch/lpc21/subsystems/imu/imu_b2_arch.c | 3 +++ sw/airborne/subsystems/imu/imu_b2.c | 2 ++ sw/airborne/subsystems/imu/imu_b2.h | 17 ++++++++++++++++- 4 files changed, 27 insertions(+), 7 deletions(-) diff --git a/conf/autopilot/subsystems/rotorcraft/imu_b2_v1.2.makefile b/conf/autopilot/subsystems/rotorcraft/imu_b2_v1.2.makefile index 91ba3d16d4..b412070be6 100644 --- a/conf/autopilot/subsystems/rotorcraft/imu_b2_v1.2.makefile +++ b/conf/autopilot/subsystems/rotorcraft/imu_b2_v1.2.makefile @@ -42,7 +42,6 @@ # imu Booz2 v1.2 imu_CFLAGS += -DIMU_TYPE_H=\"subsystems/imu/imu_b2.h\" -imu_CFLAGS += -DIMU_B2_MAG_TYPE=IMU_B2_MAG_HMC5843 imu_CFLAGS += -DIMU_B2_VERSION_1_2 imu_srcs += $(SRC_SUBSYSTEMS)/imu.c imu_srcs += $(SRC_SUBSYSTEMS)/imu/imu_b2.c @@ -51,15 +50,16 @@ imu_srcs += $(SRC_ARCH)/subsystems/imu/imu_b2_arch.c imu_srcs += peripherals/max1168.c imu_srcs += $(SRC_ARCH)/peripherals/max1168_arch.c -imu_srcs += peripherals/hmc5843.c -imu_srcs += $(SRC_ARCH)/peripherals/hmc5843_arch.c - ifeq ($(ARCH), lpc21) imu_CFLAGS += -DSSP_VIC_SLOT=9 imu_CFLAGS += -DMAX1168_EOC_VIC_SLOT=8 -#FIXME ms2100 not used on this imu -imu_CFLAGS += -DMS2100_DRDY_VIC_SLOT=12 +imu_CFLAGS += -DIMU_B2_MAG_TYPE=IMU_B2_MAG_HMC58XX +imu_CFLAGS += -DHMC58XX_I2C_DEVICE=i2c1 -DUSE_I2C1 +imu_srcs += peripherals/hmc58xx.c else ifeq ($(ARCH), stm32) +imu_CFLAGS += -DIMU_B2_MAG_TYPE=IMU_B2_MAG_HMC5843 +imu_srcs += peripherals/hmc5843.c +imu_srcs += $(SRC_ARCH)/peripherals/hmc5843_arch.c imu_CFLAGS += -DUSE_SPI2 -DUSE_DMA1_C4_IRQ -DUSE_EXTI2_IRQ -DUSE_SPI2_IRQ imu_CFLAGS += -DMAX_1168_DRDY_PORT=$(MAX_1168_DRDY_PORT) imu_CFLAGS += -DMAX_1168_DRDY_PORT_SOURCE=$(MAX_1168_DRDY_PORT_SOURCE) diff --git a/sw/airborne/arch/lpc21/subsystems/imu/imu_b2_arch.c b/sw/airborne/arch/lpc21/subsystems/imu/imu_b2_arch.c index 0b98aee11e..6cb17e1fb6 100644 --- a/sw/airborne/arch/lpc21/subsystems/imu/imu_b2_arch.c +++ b/sw/airborne/arch/lpc21/subsystems/imu/imu_b2_arch.c @@ -96,6 +96,9 @@ void imu_periodic(void) { #if defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_AMI601 RunOnceEvery(10, { ami601_read(); }); #endif +#if defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC58XX + RunOnceEvery(5,Hmc58xxPeriodic()); +#endif } diff --git a/sw/airborne/subsystems/imu/imu_b2.c b/sw/airborne/subsystems/imu/imu_b2.c index 5d4bf680a6..a41c6e9c37 100644 --- a/sw/airborne/subsystems/imu/imu_b2.c +++ b/sw/airborne/subsystems/imu/imu_b2.c @@ -34,6 +34,8 @@ void imu_impl_init(void) { ami601_init(); #elif defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC5843 hmc5843_init(); +#elif defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC58XX + hmc58xx_init(); #endif } diff --git a/sw/airborne/subsystems/imu/imu_b2.h b/sw/airborne/subsystems/imu/imu_b2.h index 2c076d03ad..1860501be9 100644 --- a/sw/airborne/subsystems/imu/imu_b2.h +++ b/sw/airborne/subsystems/imu/imu_b2.h @@ -33,6 +33,8 @@ #define IMU_B2_MAG_NONE 0 #define IMU_B2_MAG_MS2100 1 #define IMU_B2_MAG_AMI601 2 +#define IMU_B2_MAG_HMC5843 3 +#define IMU_B2_MAG_HMC58XX 4 #ifdef IMU_B2_VERSION_1_0 @@ -167,7 +169,7 @@ } \ } #elif defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC5843 -#include "peripherals/hmc5843.h" +include "peripherals/hmc5843.h" #define foo_handler() {} #define ImuMagEvent(_mag_handler) { \ MagEvent(foo_handler); \ @@ -179,6 +181,19 @@ hmc5843.data_available = FALSE; \ } \ } +#elif defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC58XX +#include "peripherals/hmc58xx.h" +#define foo_handler() {} +#define ImuMagEvent(_mag_handler) { \ + MagEvent(foo_handler); \ + if (hmc58xx_data_available) { \ + imu.mag_unscaled.x = hmc58xx_data.x; \ + imu.mag_unscaled.y = hmc58xx_data.y; \ + imu.mag_unscaled.z = hmc58xx_data.z; \ + _mag_handler(); \ + hmc58xx_data_available = FALSE; \ + } \ + } #else #define ImuMagEvent(_mag_handler) {} #endif From 99f25faf466b8fdc9b25b85809205c74f7f4ea38 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 16 Dec 2011 12:15:56 +0100 Subject: [PATCH 043/112] baro_board module: only use ADS1114 for navgo and umarim --- conf/modules/baro_board.xml | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/conf/modules/baro_board.xml b/conf/modules/baro_board.xml index 4ace2ff541..020bd730e5 100644 --- a/conf/modules/baro_board.xml +++ b/conf/modules/baro_board.xml @@ -9,11 +9,19 @@ - - - - + + +ifeq ($(BOARD), navgo) +ap.CFLAGS += -DUSE_I2C1 -DUSE_ADS1114_1 +ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 +ap.srcs += peripherals/ads1114.c +else ifeq ($(BOARD), umarim) +ap.CFLAGS += -DUSE_I2C1 -DUSE_ADS1114_1 +ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 +ap.srcs += peripherals/ads1114.c +endif + From 98cb9c414a35e670a41664b0ee1bdccf0af92741 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 16 Dec 2011 12:21:30 +0100 Subject: [PATCH 044/112] added baro_downlink_raw for lisa_l baro_board, but this is not very nice... there should be no downlink in baro implementation --- sw/airborne/boards/lisa_l/baro_board.c | 14 ++++++++++++++ sw/airborne/boards/lisa_l/baro_board.h | 2 ++ 2 files changed, 16 insertions(+) diff --git a/sw/airborne/boards/lisa_l/baro_board.c b/sw/airborne/boards/lisa_l/baro_board.c index 11829b5acf..1ca4f2abae 100644 --- a/sw/airborne/boards/lisa_l/baro_board.c +++ b/sw/airborne/boards/lisa_l/baro_board.c @@ -1,6 +1,15 @@ #include "subsystems/sensors/baro.h" +// Downlink +#include "mcu_periph/uart.h" +#include "messages.h" +#include "subsystems/datalink/downlink.h" + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + struct Baro baro; struct BaroBoard baro_board; struct i2c_transaction baro_trans; @@ -23,6 +32,11 @@ void baro_init(void) { baro_board.status = LBS_UNINITIALIZED; } +void baro_downlink_raw( void ) +{ + DOWNLINK_SEND_BARO_RAW(DefaultChannel,&baro.absolute,&baro.differential); +} + void baro_periodic(void) { // check i2c_done diff --git a/sw/airborne/boards/lisa_l/baro_board.h b/sw/airborne/boards/lisa_l/baro_board.h index 4eec5cfdee..4f988156eb 100644 --- a/sw/airborne/boards/lisa_l/baro_board.h +++ b/sw/airborne/boards/lisa_l/baro_board.h @@ -31,6 +31,8 @@ struct BaroBoard { extern struct BaroBoard baro_board; extern struct i2c_transaction baro_trans; +extern void baro_downlink_raw(void); + extern void baro_board_send_reset(void); extern void baro_board_send_config_abs(void); extern void baro_board_send_config_diff(void); From c1a3c45730a0561bb70af311331745cc62c50644 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 19 Dec 2011 15:11:05 +0100 Subject: [PATCH 045/112] renamed GCS arguments: google_fill to maps_fill and no_google_http to maps_no_http --- sw/ground_segment/cockpit/gcs.ml | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/sw/ground_segment/cockpit/gcs.ml b/sw/ground_segment/cockpit/gcs.ml index 6f832fa8a0..488aeb7f30 100644 --- a/sw/ground_segment/cockpit/gcs.ml +++ b/sw/ground_segment/cockpit/gcs.ml @@ -347,7 +347,7 @@ let options = "-center_ac", Arg.Set auto_center_new_ac, "Centers the map on any new A/C"; "-edit", Arg.Unit (fun () -> edit := true; layout_file := "editor.xml"), "Flight plan editor"; "-fullscreen", Arg.Set fullscreen, "Fullscreen window"; - "-google_fill", Arg.Set GM.auto, "Google maps auto fill"; + "-maps_fill", Arg.Set GM.auto, "Automatically start loading background maps"; "-ign", Arg.String (fun s -> ign:=true; IGN.data_path := s), "IGN tiles path"; "-lambertIIe", Arg.Unit (fun () -> projection:=G.LambertIIe),"Switch to LambertIIe projection"; "-layout", Arg.Set_string layout_file, (sprintf " GUI layout. Default: %s" !layout_file); @@ -356,12 +356,12 @@ let options = "-mercator", Arg.Unit (fun () -> projection:=G.Mercator),"Switch to (Google Maps) Mercator projection, default"; "-mplayer", Arg.Set_string mplayer, "Launch mplayer with the given argument as X plugin"; "-no_alarm", Arg.Set no_alarm, "Disables alarm page"; - "-no_google_http", Arg.Unit (fun () -> Gm.set_policy Gm.NoHttp), "Switch off Google Maps downloading"; + "-maps_no_http", Arg.Unit (fun () -> Gm.set_policy Gm.NoHttp), "Switch off downloading of maps, always use cached maps"; "-ortho", Arg.Set_string get_bdortho, "IGN tiles path"; "-osm", Arg.Unit (fun () -> Gm.set_maps_source Gm.OSM), "Use OpenStreetMap database (default is Google)"; "-ms", Arg.Unit (fun () -> Gm.set_maps_source Gm.MS), "Use Microsoft maps database (default is Google)"; "-particules", Arg.Set display_particules, "Display particules"; - "-plugin", Arg.Set_string plugin_window, "External X application (launched with the id of the plugin window as argument)"; + "-plugin", Arg.Set_string plugin_window, "External X application (launched with the id of the plugin window as argument)"; "-ref", Arg.Set_string geo_ref, "Geographic ref (e.g. 'WGS84 43.605 1.443')"; "-speech", Arg.Set Speech.active, "Enable vocal messages"; "-srtm", Arg.Set srtm, "Enable SRTM elevation display"; From eca7bbaa18fada11a55fda9cb0830856ffb26ff5 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 22 Dec 2011 16:31:05 +0100 Subject: [PATCH 046/112] removed UNTILT_ACCEL define from airframe files. This define is long obsolete, "untilting of accels" in rotorcraft ins is always done since 2009 --- conf/airframes/CDW/debug_i2c.xml | 1 - conf/airframes/ENAC/quadrotor/booz2_g1.xml | 1 - conf/airframes/ENAC/quadrotor/g1_vision.xml | 1 - conf/airframes/ENAC/quadrotor/mkk1-vision.xml | 1 - conf/airframes/ENAC/quadrotor/mkk1.xml | 1 - conf/airframes/ENAC/quadrotor/nova1.xml | 1 - conf/airframes/NoVa_L.xml | 1 - conf/airframes/Poine/booz2_a7.xml | 1 - 8 files changed, 8 deletions(-) diff --git a/conf/airframes/CDW/debug_i2c.xml b/conf/airframes/CDW/debug_i2c.xml index db334d1447..757f5d9dc1 100644 --- a/conf/airframes/CDW/debug_i2c.xml +++ b/conf/airframes/CDW/debug_i2c.xml @@ -162,7 +162,6 @@
-
diff --git a/conf/airframes/ENAC/quadrotor/booz2_g1.xml b/conf/airframes/ENAC/quadrotor/booz2_g1.xml index 345cdd9621..6b639e148d 100644 --- a/conf/airframes/ENAC/quadrotor/booz2_g1.xml +++ b/conf/airframes/ENAC/quadrotor/booz2_g1.xml @@ -158,7 +158,6 @@
-
diff --git a/conf/airframes/ENAC/quadrotor/g1_vision.xml b/conf/airframes/ENAC/quadrotor/g1_vision.xml index 521d7c87ce..f6833aa79e 100644 --- a/conf/airframes/ENAC/quadrotor/g1_vision.xml +++ b/conf/airframes/ENAC/quadrotor/g1_vision.xml @@ -131,7 +131,6 @@
-
diff --git a/conf/airframes/ENAC/quadrotor/mkk1-vision.xml b/conf/airframes/ENAC/quadrotor/mkk1-vision.xml index 03f539783f..54afa6cd75 100644 --- a/conf/airframes/ENAC/quadrotor/mkk1-vision.xml +++ b/conf/airframes/ENAC/quadrotor/mkk1-vision.xml @@ -164,7 +164,6 @@
-
diff --git a/conf/airframes/ENAC/quadrotor/mkk1.xml b/conf/airframes/ENAC/quadrotor/mkk1.xml index ee3afbe1c7..f574321c9f 100644 --- a/conf/airframes/ENAC/quadrotor/mkk1.xml +++ b/conf/airframes/ENAC/quadrotor/mkk1.xml @@ -194,7 +194,6 @@
-
diff --git a/conf/airframes/ENAC/quadrotor/nova1.xml b/conf/airframes/ENAC/quadrotor/nova1.xml index a3a05aadf2..3198cd7af5 100644 --- a/conf/airframes/ENAC/quadrotor/nova1.xml +++ b/conf/airframes/ENAC/quadrotor/nova1.xml @@ -165,7 +165,6 @@
-
diff --git a/conf/airframes/NoVa_L.xml b/conf/airframes/NoVa_L.xml index e4a4e36889..42794dc1bb 100644 --- a/conf/airframes/NoVa_L.xml +++ b/conf/airframes/NoVa_L.xml @@ -190,7 +190,6 @@
-
diff --git a/conf/airframes/Poine/booz2_a7.xml b/conf/airframes/Poine/booz2_a7.xml index 895ac7e33b..8b408aeed4 100644 --- a/conf/airframes/Poine/booz2_a7.xml +++ b/conf/airframes/Poine/booz2_a7.xml @@ -162,7 +162,6 @@
-
From 31ff0c23a82cbfcb3bdaacca70b7429fa07a7965 Mon Sep 17 00:00:00 2001 From: lamestllama Date: Fri, 23 Dec 2011 13:27:46 +1030 Subject: [PATCH 047/112] makefie changes to allow osx binary installer --- conf/autopilot/subsystems/fixedwing/autopilot.makefile | 2 +- sw/ground_segment/lpc21iap/Makefile | 4 ++-- sw/ground_segment/misc/Makefile | 5 +++-- sw/lib/ocaml/ivy/Makefile | 7 +++++-- 4 files changed, 11 insertions(+), 7 deletions(-) diff --git a/conf/autopilot/subsystems/fixedwing/autopilot.makefile b/conf/autopilot/subsystems/fixedwing/autopilot.makefile index 25687b7151..feb2496d0b 100644 --- a/conf/autopilot/subsystems/fixedwing/autopilot.makefile +++ b/conf/autopilot/subsystems/fixedwing/autopilot.makefile @@ -178,7 +178,7 @@ ap_srcs += $(SRC_FIXEDWING)/estimator.c UNAME = $(shell uname -s) ifeq ("$(UNAME)","Darwin") - sim.CFLAGS += -I/opt/local/include/ + sim.CFLAGS += -I/opt/paparazzi/include/ -I/opt/local/include/ endif sim.CFLAGS += $(CPPFLAGS) diff --git a/sw/ground_segment/lpc21iap/Makefile b/sw/ground_segment/lpc21iap/Makefile index e3fab50201..dc4a954a37 100644 --- a/sw/ground_segment/lpc21iap/Makefile +++ b/sw/ground_segment/lpc21iap/Makefile @@ -27,8 +27,8 @@ endif UNAME = $(shell uname -s) ifeq ("$(UNAME)","Darwin") - INCLUDES=-I/opt/local/include/ - LIBRARYS=-L/opt/local/lib + LIBRARYS = -L /opt/paparazzi/lib -L /opt/local/lib + INCLUDES = -I /opt/paparazzi/include -I /opt/local/include/ endif diff --git a/sw/ground_segment/misc/Makefile b/sw/ground_segment/misc/Makefile index d7cf0118fb..7870fe7e62 100644 --- a/sw/ground_segment/misc/Makefile +++ b/sw/ground_segment/misc/Makefile @@ -1,7 +1,8 @@ UNAME = $(shell uname -s) ifeq ("$(UNAME)","Darwin") - LIBRARYS = -L/opt/local/lib + LIBRARYS = -L /opt/paparazzi/lib -L /opt/local/lib + INCLUDES = -I /opt/paparazzi/include -I /opt/local/include/ else LIBRARYS = -s endif @@ -19,4 +20,4 @@ kestrel2ivy: kestrel2ivy.o g++ -o kestrel2ivy kestrel2ivy.o $(LIBRARYS) -livy %.o : %.c - gcc -c -O2 -Wall -I /opt/local/include/ $< + gcc -c -O2 -Wall $(INCLUDES) $< diff --git a/sw/lib/ocaml/ivy/Makefile b/sw/lib/ocaml/ivy/Makefile index 24613416c7..574935c6d6 100644 --- a/sw/lib/ocaml/ivy/Makefile +++ b/sw/lib/ocaml/ivy/Makefile @@ -49,8 +49,11 @@ TKIVYCMX= $(TKIVY:.ml=.cmx) UNAME = $(shell uname -s) +UNAME = $(shell uname -s) + ifeq ("$(UNAME)","Darwin") - LIBRARYS = -L/opt/local/lib + LIBRARYS = -L /opt/paparazzi/lib -L /opt/local/lib + INCLUDES = -I /opt/paparazzi/include -I /opt/local/include/ endif LIBS = ivy-ocaml.cma ivy-ocaml.cmxa glibivy-ocaml.cma glibivy-ocaml.cmxa @@ -102,7 +105,7 @@ tkivy-ocaml.cmxa : $(TKIVYCMX) civy.o ctkivy.o $(OCAMLC) $(OCAMLFLAGS) $(INCLUDES) -c $< .c.o : - $(CC) -Wall -c $(FPIC) -I /opt/local/include/ $(OCAMLINC) $(GLIBINC) $< + $(CC) -Wall -c $(FPIC) $(INCLUDES) $(OCAMLINC) $(GLIBINC) $< .mli.cmi : $(OCAMLMLI) $(OCAMLFLAGS) -c $< .ml.cmx : From 563fd0bfc88ccc8d0889ce1189d23472617ab931 Mon Sep 17 00:00:00 2001 From: lamestllama Date: Sat, 24 Dec 2011 00:11:16 +1030 Subject: [PATCH 048/112] headers have been moved in libopencm3 --- sw/airborne/arch/stm32/subsystems/settings_arch.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/arch/stm32/subsystems/settings_arch.c b/sw/airborne/arch/stm32/subsystems/settings_arch.c index 9ac5d761aa..812f4c31c0 100644 --- a/sw/airborne/arch/stm32/subsystems/settings_arch.c +++ b/sw/airborne/arch/stm32/subsystems/settings_arch.c @@ -37,11 +37,11 @@ #if defined(STM32F1) || defined(STM32F2) || defined(STM32F4) #include -#include #else #include -#include #endif + +#include #include struct FlashInfo { From 1aff2222f50f016906b396958d414fec8b08ad63 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Tue, 27 Dec 2011 19:11:39 +0100 Subject: [PATCH 049/112] Chimu-J on TWOG --- conf/airframes/CDW/ChimuJTinyFwSpi.xml | 195 +++++++++++++++++++++++++ 1 file changed, 195 insertions(+) create mode 100644 conf/airframes/CDW/ChimuJTinyFwSpi.xml diff --git a/conf/airframes/CDW/ChimuJTinyFwSpi.xml b/conf/airframes/CDW/ChimuJTinyFwSpi.xml new file mode 100644 index 0000000000..98868c8e66 --- /dev/null +++ b/conf/airframes/CDW/ChimuJTinyFwSpi.xml @@ -0,0 +1,195 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + + + + + + + + + + + + +
+ + + + + + + + + + + + + +
+ + +
+ +
+ + +
+ +
+ + + + + +
+ +
+ + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + +
+ +
+ + + + + + + + +
+ +
+ + + + + + + +
+ +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
From b75fc710bf675fd307298b2e9c141f1ac7bd49ad Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 5 Jan 2012 17:26:38 +0100 Subject: [PATCH 050/112] LED 2 and 3 for Lisa/M --- sw/airborne/boards/lisa_m_1.0.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/sw/airborne/boards/lisa_m_1.0.h b/sw/airborne/boards/lisa_m_1.0.h index 0fa3a7f7d4..a9dfc3bff4 100644 --- a/sw/airborne/boards/lisa_m_1.0.h +++ b/sw/airborne/boards/lisa_m_1.0.h @@ -15,9 +15,15 @@ #define LED_2_BANK #define LED_2_GPIO GPIOC #define LED_2_GPIO_CLK RCC_APB2Periph_GPIOC -#define LED_2_GPIO_PIN GPIO_Pin_13 +#define LED_2_GPIO_PIN GPIO_Pin_5 #define LED_2_AFIO_REMAP ((void)0) +#define LED_3_BANK +#define LED_3_GPIO GPIOC +#define LED_3_GPIO_CLK RCC_APB2Periph_GPIOC +#define LED_3_GPIO_PIN GPIO_Pin_2 +#define LED_3_AFIO_REMAP ((void)0) + /* configuration for aspirin - and more generaly IMUs */ #define IMU_ACC_DRDY_RCC_GPIO RCC_APB2Periph_GPIOB From d94719bef88236de6f18f1d34887aec44b151f49 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 7 Jan 2012 22:04:40 +0100 Subject: [PATCH 051/112] fix inlude of downlink for lisa/l baro board --- sw/airborne/boards/lisa_l/baro_board.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/boards/lisa_l/baro_board.c b/sw/airborne/boards/lisa_l/baro_board.c index 1ca4f2abae..1442faef8f 100644 --- a/sw/airborne/boards/lisa_l/baro_board.c +++ b/sw/airborne/boards/lisa_l/baro_board.c @@ -4,7 +4,7 @@ // Downlink #include "mcu_periph/uart.h" #include "messages.h" -#include "subsystems/datalink/downlink.h" +#include "downlink.h" #ifndef DOWNLINK_DEVICE #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE From 68a0c5c5265c5e7630b5a566dfb9e61c0d58c2c2 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 9 Jan 2012 21:54:56 +0100 Subject: [PATCH 052/112] fix usb_tunnel: use proper CheckFreeSpace macros --- sw/airborne/arch/lpc21/usb_tunnel.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/arch/lpc21/usb_tunnel.c b/sw/airborne/arch/lpc21/usb_tunnel.c index c2acef1e61..035cebda84 100644 --- a/sw/airborne/arch/lpc21/usb_tunnel.c +++ b/sw/airborne/arch/lpc21/usb_tunnel.c @@ -67,7 +67,7 @@ int main( void ) { inc = Uart0Getch(); VCOM_putchar(inc); } - if (VCOM_check_available() && uart0_check_free_space(1)) { + if (VCOM_check_available() && Uart0CheckFreeSpace(1)) { LED_ON(2); tx_time = T0TC; inc = VCOM_getchar(); @@ -84,7 +84,7 @@ int main( void ) { inc = Uart1Getch(); VCOM_putchar(inc); } - if (VCOM_check_available() && uart1_check_free_space(1)) { + if (VCOM_check_available() && Uart1CheckFreeSpace(1)) { LED_ON(2); tx_time = T0TC; inc = VCOM_getchar(); From a146aa9809e3f1f3b700eaf0f141f062d1429919 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 10 Jan 2012 17:10:12 +0100 Subject: [PATCH 053/112] gitignore html/ folder (contains gh-pages branch) --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 6a0bf36496..b16f9b2ad5 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,6 @@ +# ignore html dir for github pages +/html + *.so *.[oa] *.out From d61cd19cc95eec352dd52f4cf19fcdc35500b1ab Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 10 Jan 2012 23:04:55 +0100 Subject: [PATCH 054/112] output doxygen generated html files to html dir for publishing on github pages --- Doxyfile | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Doxyfile b/Doxyfile index 934897d58e..de5339703f 100644 --- a/Doxyfile +++ b/Doxyfile @@ -25,20 +25,20 @@ DOXYFILE_ENCODING = UTF-8 # The PROJECT_NAME tag is a single word (or a sequence of words surrounded # by quotes) that should identify the project. -PROJECT_NAME = Paparazzi +PROJECT_NAME = Paparazzi UAV # The PROJECT_NUMBER tag can be used to enter a project or revision number. # This could be handy for archiving the generated documentation or # if some version control system is used. -PROJECT_NUMBER = 4 +PROJECT_NUMBER = 3.5 # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) # base path where the generated documentation will be put. # If a relative path is entered, it will be relative to the location # where doxygen was started. If left blank the current directory will be used. -OUTPUT_DIRECTORY = dox +OUTPUT_DIRECTORY = html # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create # 4096 sub-directories (in 2 levels) under the output directory of each output @@ -773,7 +773,7 @@ GENERATE_HTML = YES # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `html' will be used as the default path. -HTML_OUTPUT = html +HTML_OUTPUT = doxygen # The HTML_FILE_EXTENSION tag can be used to specify the file extension for # each generated HTML page (for example: .htm,.php,.asp). If it is left blank From fc2efa720e4abae4542d245d35b6f873ccf1b64c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 11 Jan 2012 19:49:33 +0100 Subject: [PATCH 055/112] updaetd Doxyfile for documentation under paparazzi.github.com/docs --- Doxyfile | 370 ++++++++++++++++++++++++++++++++++++++++--------------- 1 file changed, 269 insertions(+), 101 deletions(-) diff --git a/Doxyfile b/Doxyfile index de5339703f..b8d4474f7d 100644 --- a/Doxyfile +++ b/Doxyfile @@ -1,4 +1,4 @@ -# Doxyfile 1.6.3 +# Doxyfile 1.7.4 # This file describes the settings to be used by the documentation system # doxygen (www.doxygen.org) for a project @@ -25,7 +25,7 @@ DOXYFILE_ENCODING = UTF-8 # The PROJECT_NAME tag is a single word (or a sequence of words surrounded # by quotes) that should identify the project. -PROJECT_NAME = Paparazzi UAV +PROJECT_NAME = "Paparazzi UAV" # The PROJECT_NUMBER tag can be used to enter a project or revision number. # This could be handy for archiving the generated documentation or @@ -33,6 +33,19 @@ PROJECT_NAME = Paparazzi UAV PROJECT_NUMBER = 3.5 +# Using the PROJECT_BRIEF tag one can provide an optional one line description +# for a project that appears at the top of each page and should give viewer +# a quick idea about the purpose of the project. Keep the description short. + +PROJECT_BRIEF = "Paparazzi is a free software Unmanned (Air) Vehicle System." + +# With the PROJECT_LOGO tag one can specify an logo or icon that is +# included in the documentation. The maximum height of the logo should not +# exceed 55 pixels and the maximum width should not exceed 200 pixels. +# Doxygen will copy the logo to the output directory. + +PROJECT_LOGO = data/pictures/penguin_icon.png + # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) # base path where the generated documentation will be put. # If a relative path is entered, it will be relative to the location @@ -57,7 +70,7 @@ CREATE_SUBDIRS = NO # Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German, # Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English # messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian, -# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrilic, Slovak, +# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak, # Slovene, Spanish, Swedish, Ukrainian, and Vietnamese. OUTPUT_LANGUAGE = English @@ -126,7 +139,7 @@ STRIP_FROM_PATH = STRIP_FROM_INC_PATH = # If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter -# (but less readable) file names. This can be useful is your file systems +# (but less readable) file names. This can be useful if your file system # doesn't support long names like on DOS, Mac, or CD-ROM. SHORT_NAMES = NO @@ -207,14 +220,15 @@ OPTIMIZE_FOR_FORTRAN = NO OPTIMIZE_OUTPUT_VHDL = NO -# Doxygen selects the parser to use depending on the extension of the files it parses. -# With this tag you can assign which parser to use for a given extension. -# Doxygen has a built-in mapping, but you can override or extend it using this tag. -# The format is ext=language, where ext is a file extension, and language is one of -# the parsers supported by doxygen: IDL, Java, Javascript, C#, C, C++, D, PHP, -# Objective-C, Python, Fortran, VHDL, C, C++. For instance to make doxygen treat -# .inc files as Fortran files (default is PHP), and .f files as C (default is Fortran), -# use: inc=Fortran f=C. Note that for custom extensions you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. +# Doxygen selects the parser to use depending on the extension of the files it +# parses. With this tag you can assign which parser to use for a given extension. +# Doxygen has a built-in mapping, but you can override or extend it using this +# tag. The format is ext=language, where ext is a file extension, and language +# is one of the parsers supported by doxygen: IDL, Java, Javascript, CSharp, C, +# C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, C++. For instance to make +# doxygen treat .inc files as Fortran files (default is PHP), and .f files as C +# (default is Fortran), use: inc=Fortran f=C. Note that for custom extensions +# you also need to set FILE_PATTERNS otherwise the files are not read by doxygen. EXTENSION_MAPPING = @@ -222,7 +236,7 @@ EXTENSION_MAPPING = # to include (a tag file for) the STL sources as input, then you should # set this tag to YES in order to let doxygen match functions declarations and # definitions whose arguments contain STL classes (e.g. func(std::string); v.s. -# func(std::string) {}). This also make the inheritance and collaboration +# func(std::string) {}). This also makes the inheritance and collaboration # diagrams that involve STL classes more complete and accurate. BUILTIN_STL_SUPPORT = NO @@ -240,7 +254,7 @@ SIP_SUPPORT = NO # For Microsoft's IDL there are propget and propput attributes to indicate getter # and setter methods for a property. Setting this option to YES (the default) -# will make doxygen to replace the get and set methods by a property in the +# will make doxygen replace the get and set methods by a property in the # documentation. This will only work if the methods are indeed getting or # setting a simple type. If this is not the case, or you want to show the # methods anyway, you should set this option to NO. @@ -262,6 +276,13 @@ DISTRIBUTE_GROUP_DOC = NO SUBGROUPING = YES +# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and +# unions are shown inside the group in which they are included (e.g. using +# @ingroup) instead of on a separate page (for HTML and Man pages) or +# section (for LaTeX and RTF). + +INLINE_GROUPED_CLASSES = NO + # When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum # is documented as struct, union, or enum with the name of the typedef. So # typedef struct TypeS {} TypeT, will appear in the documentation as a struct @@ -278,10 +299,10 @@ TYPEDEF_HIDES_STRUCT = NO # For small to medium size projects (<1000 input files) the default value is # probably good enough. For larger projects a too small cache size can cause # doxygen to be busy swapping symbols to and from disk most of the time -# causing a significant performance penality. +# causing a significant performance penalty. # If the system has enough physical memory increasing the cache will improve the # performance by keeping more symbols in memory. Note that the value works on -# a logarithmic scale so increasing the size by one will rougly double the +# a logarithmic scale so increasing the size by one will roughly double the # memory usage. The cache size is given by this formula: # 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0, # corresponding to a cache size of 2^16 = 65536 symbols @@ -326,7 +347,7 @@ EXTRACT_LOCAL_METHODS = NO # extracted and appear in the documentation as a namespace called # 'anonymous_namespace{file}', where file will be replaced with the base # name of the file that contains the anonymous namespace. By default -# anonymous namespace are hidden. +# anonymous namespaces are hidden. EXTRACT_ANON_NSPACES = NO @@ -411,7 +432,13 @@ SORT_MEMBER_DOCS = YES SORT_BRIEF_DOCS = NO -# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the (brief and detailed) documentation of class members so that constructors and destructors are listed first. If set to NO (the default) the constructors will appear in the respective orders defined by SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. +# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen +# will sort the (brief and detailed) documentation of class members so that +# constructors and destructors are listed first. If set to NO (the default) +# the constructors will appear in the respective orders defined by +# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS. +# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO +# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO. SORT_MEMBERS_CTORS_1ST = NO @@ -431,6 +458,15 @@ SORT_GROUP_NAMES = NO SORT_BY_SCOPE_NAME = NO +# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to +# do proper type resolution of all parameters of a function it will reject a +# match between the prototype and the implementation of a member function even +# if there is only one candidate or it is obvious which candidate to choose +# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen +# will still accept a match between prototype and implementation in such cases. + +STRICT_PROTO_MATCHING = NO + # The GENERATE_TODOLIST tag can be used to enable (YES) or # disable (NO) the todo list. This list is created by putting \todo # commands in the documentation. @@ -461,10 +497,10 @@ GENERATE_DEPRECATEDLIST= YES ENABLED_SECTIONS = # The MAX_INITIALIZER_LINES tag determines the maximum number of lines -# the initial value of a variable or define consists of for it to appear in +# the initial value of a variable or macro consists of for it to appear in # the documentation. If the initializer consists of more lines than specified # here it will be hidden. Use a value of 0 to hide initializers completely. -# The appearance of the initializer of individual variables and defines in the +# The appearance of the initializer of individual variables and macros in the # documentation can be controlled using \showinitializer or \hideinitializer # command in the documentation regardless of this setting. @@ -489,8 +525,7 @@ SHOW_DIRECTORIES = YES SHOW_FILES = YES # Set the SHOW_NAMESPACES tag to NO to disable the generation of the -# Namespaces page. -# This will remove the Namespaces entry from the Quick Index +# Namespaces page. This will remove the Namespaces entry from the Quick Index # and from the Folder Tree View (if specified). The default is YES. SHOW_NAMESPACES = YES @@ -505,12 +540,12 @@ SHOW_NAMESPACES = YES FILE_VERSION_FILTER = -# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed by -# doxygen. The layout file controls the global structure of the generated output files -# in an output format independent way. The create the layout file that represents -# doxygen's defaults, run doxygen with the -l option. You can optionally specify a -# file name after the option, if omitted DoxygenLayout.xml will be used as the name -# of the layout file. +# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed +# by doxygen. The layout file controls the global structure of the generated +# output files in an output format independent way. The create the layout file +# that represents doxygen's defaults, run doxygen with the -l option. +# You can optionally specify a file name after the option, if omitted +# DoxygenLayout.xml will be used as the name of the layout file. LAYOUT_FILE = @@ -542,7 +577,7 @@ WARN_IF_UNDOCUMENTED = YES WARN_IF_DOC_ERROR = YES -# This WARN_NO_PARAMDOC option can be abled to get warnings for +# The WARN_NO_PARAMDOC option can be enabled to get warnings for # functions that are documented, but have no documentation for their parameters # or return value. If set to NO (the default) doxygen will only warn about # wrong or incomplete parameter documentation, but not about the absence of @@ -574,7 +609,7 @@ WARN_LOGFILE = # directories like "/usr/src/myproject". Separate the files or directories # with spaces. -INPUT = sw/airborne sw/airborne/math +INPUT = sw/airborne # 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 @@ -588,8 +623,9 @@ INPUT_ENCODING = UTF-8 # FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp # and *.h) to filter out the source-files in the directories. If left # blank the following patterns are tested: -# *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx -# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py *.f90 +# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh +# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py +# *.f90 *.f *.for *.vhd *.vhdl FILE_PATTERNS = @@ -597,16 +633,30 @@ FILE_PATTERNS = # should be searched for input files as well. Possible values are YES and NO. # If left blank NO is used. -RECURSIVE = NO +RECURSIVE = YES # The EXCLUDE tag can be used to specify files and/or directories that should # 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 = var +EXCLUDE = sw/airborne/csc/ \ + sw/airborne/obsolete/ \ + sw/airborne/booz/ \ + sw/airborne/test/ \ + sw/airborne/arch/avr/ \ + sw/airborne/firmwares/non_ap/ \ + sw/airborne/firmwares/logger/ \ + sw/airborne/firmwares/vor/ \ + sw/airborne/firmwares/wind_tunnel/ \ + sw/airborne/firmwares/beth/ \ + sw/airborne/firmwares/motor_bench/ \ + sw/airborne/fms/ \ + sw/airborne/arch/lpc21/test/ \ + sw/airborne/arch/lpc21/efsl/ \ + sw/airborne/arch/lpc21/lpcusb/ # The EXCLUDE_SYMLINKS tag can be used select whether or not files or -# directories that are symbolic links (a Unix filesystem feature) are excluded +# directories that are symbolic links (a Unix file system feature) are excluded # from the input. EXCLUDE_SYMLINKS = NO @@ -658,20 +708,17 @@ IMAGE_PATH = # by executing (via popen()) the command , where # is the value of the INPUT_FILTER tag, and is the name of an # input file. Doxygen will then use the output that the filter program writes -# to standard output. -# If FILTER_PATTERNS is specified, this tag will be +# to standard output. If FILTER_PATTERNS is specified, this tag will be # ignored. INPUT_FILTER = # The FILTER_PATTERNS tag can be used to specify filters on a per file pattern -# basis. -# Doxygen will compare the file name with each pattern and apply the -# filter if there is a match. -# The filters are a list of the form: +# basis. Doxygen will compare the file name with each pattern and apply the +# filter if there is a match. The filters are a list of the form: # pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further -# info on how filters are used. If FILTER_PATTERNS is empty, INPUT_FILTER -# is applied to all files. +# info on how filters are used. If FILTER_PATTERNS is empty or if +# non of the patterns match the file name, INPUT_FILTER is applied. FILTER_PATTERNS = @@ -681,6 +728,14 @@ FILTER_PATTERNS = FILTER_SOURCE_FILES = NO +# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file +# pattern. A pattern will override the setting for FILTER_PATTERN (if any) +# and it is also possible to disable source filtering for a specific pattern +# using *.ext= (so without naming a filter). This option only has effect when +# FILTER_SOURCE_FILES is enabled. + +FILTER_SOURCE_PATTERNS = + #--------------------------------------------------------------------------- # configuration options related to source browsing #--------------------------------------------------------------------------- @@ -718,8 +773,7 @@ REFERENCES_RELATION = YES # If the REFERENCES_LINK_SOURCE tag is set to YES (the default) # and SOURCE_BROWSER tag is set to YES, then the hyperlinks from # functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will -# link to the source code. -# Otherwise they will link to the documentation. +# link to the source code. Otherwise they will link to the documentation. REFERENCES_LINK_SOURCE = YES @@ -745,7 +799,7 @@ VERBATIM_HEADERS = YES # of all compounds will be generated. Enable this if the project # contains a lot of classes, structs, unions or interfaces. -ALPHABETICAL_INDEX = NO +ALPHABETICAL_INDEX = YES # If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then # the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns @@ -773,7 +827,7 @@ GENERATE_HTML = YES # If a relative path is entered the value of OUTPUT_DIRECTORY will be # put in front of it. If left blank `html' will be used as the default path. -HTML_OUTPUT = doxygen +HTML_OUTPUT = docs # The HTML_FILE_EXTENSION tag can be used to specify the file extension for # each generated HTML page (for example: .htm,.php,.asp). If it is left blank @@ -783,7 +837,14 @@ HTML_FILE_EXTENSION = .html # The HTML_HEADER tag can be used to specify a personal HTML header for # each generated HTML page. If it is left blank doxygen will generate a -# standard header. +# standard header. Note that when using a custom header you are responsible +# for the proper inclusion of any scripts and style sheets that doxygen +# needs, which is dependent on the configuration options used. +# It is adviced to generate a default header using "doxygen -w html +# header.html footer.html stylesheet.css YourConfigFile" and then modify +# that header. Note that the header is subject to change so you typically +# have to redo this when upgrading to a newer version of doxygen or when +# changing the value of configuration settings such as GENERATE_TREEVIEW! HTML_HEADER = @@ -802,6 +863,40 @@ HTML_FOOTER = HTML_STYLESHEET = +# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or +# other source files which should be copied to the HTML output directory. Note +# that these files will be copied to the base HTML output directory. Use the +# $relpath$ marker in the HTML_HEADER and/or HTML_FOOTER files to load these +# files. In the HTML_STYLESHEET file, use the file name only. Also note that +# the files will be copied as-is; there are no commands or markers available. + +HTML_EXTRA_FILES = + +# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. +# Doxygen will adjust the colors in the stylesheet and background images +# according to this color. Hue is specified as an angle on a colorwheel, +# see http://en.wikipedia.org/wiki/Hue for more information. +# For instance the value 0 represents red, 60 is yellow, 120 is green, +# 180 is cyan, 240 is blue, 300 purple, and 360 is red again. +# The allowed range is 0 to 359. + +HTML_COLORSTYLE_HUE = 220 + +# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of +# the colors in the HTML output. For a value of 0 the output will use +# grayscales only. A value of 255 will produce the most vivid colors. + +HTML_COLORSTYLE_SAT = 100 + +# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to +# the luminance component of the colors in the HTML output. Values below +# 100 gradually make the output lighter, whereas values above 100 make +# the output darker. The value divided by 100 is the actual gamma applied, +# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, +# and 100 does not change the gamma. + +HTML_COLORSTYLE_GAMMA = 80 + # If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML # page will contain the date and time when the page was generated. Setting # this to NO can help when comparing the output of multiple runs. @@ -830,7 +925,8 @@ HTML_DYNAMIC_SECTIONS = YES # directory and running "make install" will install the docset in # ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find # it at startup. -# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html for more information. +# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html +# for more information. GENERATE_DOCSET = NO @@ -848,6 +944,16 @@ DOCSET_FEEDNAME = "Doxygen generated docs" DOCSET_BUNDLE_ID = org.doxygen.Project +# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely identify +# the documentation publisher. This should be a reverse domain-name style +# string, e.g. com.mycompany.MyDocSet.documentation. + +DOCSET_PUBLISHER_ID = org.doxygen.Publisher + +# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher. + +DOCSET_PUBLISHER_NAME = Publisher + # If the GENERATE_HTMLHELP tag is set to YES, additional index files # will be generated that can be used as input for tools like the # Microsoft HTML help workshop to generate a compiled HTML help file (.chm) @@ -892,10 +998,10 @@ BINARY_TOC = NO TOC_EXPAND = NO -# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and QHP_VIRTUAL_FOLDER -# are set, an additional index file will be generated that can be used as input for -# Qt's qhelpgenerator to generate a Qt Compressed Help (.qch) of the generated -# HTML documentation. +# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and +# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated +# that can be used as input for Qt's qhelpgenerator to generate a +# Qt Compressed Help (.qch) of the generated HTML documentation. GENERATE_QHP = NO @@ -917,20 +1023,24 @@ QHP_NAMESPACE = org.doxygen.Project QHP_VIRTUAL_FOLDER = doc -# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to add. -# For more information please see +# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to +# add. For more information please see # http://doc.trolltech.com/qthelpproject.html#custom-filters QHP_CUST_FILTER_NAME = -# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the custom filter to add.For more information please see -# Qt Help Project / Custom Filters. +# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the +# custom filter to add. For more information please see +# +# Qt Help Project / Custom Filters. QHP_CUST_FILTER_ATTRS = -# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this project's +# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this +# project's # filter section matches. -# Qt Help Project / Filter Attributes. +# +# Qt Help Project / Filter Attributes. QHP_SECT_FILTER_ATTRS = @@ -942,12 +1052,13 @@ QHP_SECT_FILTER_ATTRS = QHG_LOCATION = # If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files -# will be generated, which together with the HTML files, form an Eclipse help -# plugin. To install this plugin and make it available under the help contents +# will be generated, which together with the HTML files, form an Eclipse help +# plugin. To install this plugin and make it available under the help contents # menu in Eclipse, the contents of the directory containing the HTML and XML # files needs to be copied into the plugins directory of eclipse. The name of # the directory within the plugins directory should be the same as -# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before the help appears. +# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before +# the help appears. GENERATE_ECLIPSEHELP = NO @@ -963,8 +1074,10 @@ ECLIPSE_DOC_ID = org.doxygen.Project DISABLE_INDEX = NO -# This tag can be used to set the number of enum values (range [1..20]) -# that doxygen will group on one line in the generated HTML documentation. +# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values +# (range [0,1..20]) that doxygen will group on one line in the generated HTML +# documentation. Note that a value of 0 will completely suppress the enum +# values from appearing in the overview section. ENUM_VALUES_PER_LINE = 4 @@ -976,7 +1089,7 @@ ENUM_VALUES_PER_LINE = 4 # JavaScript, DHTML, CSS and frames is required (i.e. any modern browser). # Windows users are probably better off using the HTML help feature. -GENERATE_TREEVIEW = NO +GENERATE_TREEVIEW = YES # By enabling USE_INLINE_TREES, doxygen will generate the Groups, Directories, # and Class Hierarchy pages using a tree view instead of an ordered list. @@ -989,6 +1102,11 @@ USE_INLINE_TREES = NO TREEVIEW_WIDTH = 250 +# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open +# links to external symbols imported via tag files in a separate window. + +EXT_LINKS_IN_WINDOW = NO + # Use this tag to change the font size of Latex formulas included # as images in the HTML documentation. The default is 10. Note that # when you change the font size after a successful doxygen run you need @@ -997,15 +1115,50 @@ TREEVIEW_WIDTH = 250 FORMULA_FONTSIZE = 10 -# When the SEARCHENGINE tag is enabled doxygen will generate a search box for the HTML output. The underlying search engine uses javascript -# and DHTML and should work on any modern browser. Note that when using HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET) there is already a search function so this one should +# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# generated for formulas are transparent PNGs. Transparent PNGs are +# not supported properly for IE 6.0, but are supported on all modern browsers. +# Note that when changing this option you need to delete any form_*.png files +# in the HTML output before the changes have effect. + +FORMULA_TRANSPARENT = YES + +# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax +# (see http://www.mathjax.org) which uses client side Javascript for the +# rendering instead of using prerendered bitmaps. Use this if you do not +# have LaTeX installed or if you want to formulas look prettier in the HTML +# output. When enabled you also need to install MathJax separately and +# configure the path to it using the MATHJAX_RELPATH option. + +USE_MATHJAX = NO + +# When MathJax is enabled you need to specify the location relative to the +# HTML output directory using the MATHJAX_RELPATH option. The destination +# directory should contain the MathJax.js script. For instance, if the mathjax +# directory is located at the same level as the HTML output directory, then +# MATHJAX_RELPATH should be ../mathjax. The default value points to the +# mathjax.org site, so you can quickly see the result without installing +# MathJax, but it is strongly recommended to install a local copy of MathJax +# before deployment. + +MATHJAX_RELPATH = http://www.mathjax.org/mathjax + +# When the SEARCHENGINE tag is enabled doxygen will generate a search box +# for the HTML output. The underlying search engine uses javascript +# and DHTML and should work on any modern browser. Note that when using +# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets +# (GENERATE_DOCSET) there is already a search function so this one should # typically be disabled. For large projects the javascript based search engine # can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution. SEARCHENGINE = YES -# When the SERVER_BASED_SEARCH tag is enabled the search engine will be implemented using a PHP enabled web server instead of at the web client using Javascript. Doxygen will generate the search PHP script and index -# file to put on the web server. The advantage of the server based approach is that it scales better to large projects and allows full text search. The disadvances is that it is more difficult to setup +# When the SERVER_BASED_SEARCH tag is enabled the search engine will be +# implemented using a PHP enabled web server instead of at the web client +# using Javascript. Doxygen will generate the search PHP script and index +# file to put on the web server. The advantage of the server +# based approach is that it scales better to large projects and allows +# full text search. The disadvantages are that it is more difficult to setup # and does not have live searching capabilities. SERVER_BASED_SEARCH = NO @@ -1046,7 +1199,7 @@ MAKEINDEX_CMD_NAME = makeindex COMPACT_LATEX = NO # The PAPER_TYPE tag can be used to set the paper type that is used -# by the printer. Possible values are: a4, a4wide, letter, legal and +# by the printer. Possible values are: a4, letter, legal and # executive. If left blank a4wide will be used. PAPER_TYPE = a4wide @@ -1063,6 +1216,13 @@ EXTRA_PACKAGES = LATEX_HEADER = +# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for +# the generated latex document. The footer should contain everything after +# the last chapter. If it is left blank doxygen will generate a +# standard footer. Notice: only use this tag if you know what you are doing! + +LATEX_FOOTER = + # If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated # is prepared for conversion to pdf (using ps2pdf). The pdf file will # contain links (just like the HTML output) instead of page references @@ -1089,7 +1249,10 @@ LATEX_BATCHMODE = NO LATEX_HIDE_INDICES = NO -# If LATEX_SOURCE_CODE is set to YES then doxygen will include source code with syntax highlighting in the LaTeX output. Note that which sources are shown also depends on other settings such as SOURCE_BROWSER. +# If LATEX_SOURCE_CODE is set to YES then doxygen will include +# source code with syntax highlighting in the LaTeX output. +# Note that which sources are shown also depends on other settings +# such as SOURCE_BROWSER. LATEX_SOURCE_CODE = NO @@ -1229,10 +1392,8 @@ GENERATE_PERLMOD = NO PERLMOD_LATEX = NO # If the PERLMOD_PRETTY tag is set to YES the Perl module output will be -# nicely formatted so it can be parsed by a human reader. -# This is useful -# if you want to understand what is going on. -# On the other hand, if this +# nicely formatted so it can be parsed by a human reader. This is useful +# if you want to understand what is going on. On the other hand, if this # tag is set to NO the size of the Perl module output will be much smaller # and Perl will parse it just the same. @@ -1269,7 +1430,7 @@ MACRO_EXPANSION = NO EXPAND_ONLY_PREDEF = NO # If the SEARCH_INCLUDES tag is set to YES (the default) the includes files -# in the INCLUDE_PATH (see below) will be search if a #include is found. +# pointed to by INCLUDE_PATH will be searched when a #include is found. SEARCH_INCLUDES = YES @@ -1277,8 +1438,7 @@ SEARCH_INCLUDES = YES # contain include files that are not input files but should be processed by # the preprocessor. -INCLUDE_PATH = sw/include \ - sw/airborne +INCLUDE_PATH = sw/include # You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard # patterns (like *.h and *.hpp) to filter out the header-files in the @@ -1295,22 +1455,20 @@ INCLUDE_FILE_PATTERNS = # undefined via #undef or recursively expanded use the := operator # instead of the = operator. -PREDEFINED = KILL_SWITCH \ - USE_BUSS_TWI_BLMC \ - USE_AMI601 +PREDEFINED = # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then # this tag can be used to specify a list of macro names that should be expanded. # The macro definition that is found in the sources will be used. -# Use the PREDEFINED tag if you want to use a different macro definition. +# Use the PREDEFINED tag if you want to use a different macro definition that +# overrules the definition found in the source code. EXPAND_AS_DEFINED = # If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then -# doxygen's preprocessor will remove all function-like macros that are alone -# on a line, have an all uppercase name, and do not end with a semicolon. Such -# function macros are typically used for boiler-plate code, and will confuse -# the parser if not removed. +# doxygen's preprocessor will remove all references to function-like macros +# that are alone on a line, have an all uppercase name, and do not end with a +# semicolon, because these will confuse the parser if not removed. SKIP_FUNCTION_MACROS = YES @@ -1322,11 +1480,9 @@ SKIP_FUNCTION_MACROS = YES # Optionally an initial location of the external documentation # can be added for each tagfile. The format of a tag file without # this location is as follows: -# -# TAGFILES = file1 file2 ... +# TAGFILES = file1 file2 ... # Adding location for the tag files is done as follows: -# -# TAGFILES = file1=loc1 "file2 = loc2" ... +# TAGFILES = file1=loc1 "file2 = loc2" ... # where "loc1" and "loc2" can be relative or absolute paths or # URLs. If a location is present for each tag, the installdox tool # does not have to be run to correct the links. @@ -1366,9 +1522,8 @@ PERL_PATH = /usr/bin/perl # If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will # generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base # or super classes. Setting the tag to NO turns the diagrams off. Note that -# this option is superseded by the HAVE_DOT option below. This is only a -# fallback. It is recommended to install and use dot, since it yields more -# powerful graphs. +# this option also works with HAVE_DOT disabled, but it is recommended to +# install and use dot, since it yields more powerful graphs. CLASS_DIAGRAMS = YES @@ -1394,11 +1549,18 @@ HIDE_UNDOC_RELATIONS = YES HAVE_DOT = YES -# By default doxygen will write a font called FreeSans.ttf to the output -# directory and reference it in all dot files that doxygen generates. This -# font does not include all possible unicode characters however, so when you need -# these (or just want a differently looking font) you can specify the font name -# using DOT_FONTNAME. You need need to make sure dot is able to find the font, +# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is +# allowed to run in parallel. When set to 0 (the default) doxygen will +# base this on the number of processors available in the system. You can set it +# explicitly to a value larger than 0 to get control over the balance +# between CPU load and processing speed. + +DOT_NUM_THREADS = 0 + +# By default doxygen will write a font called Helvetica to the output +# directory and reference it in all dot files that doxygen generates. +# When you want a differently looking font you can specify the font name +# using DOT_FONTNAME. You need to make sure dot is able to find the font, # which can be done by putting it in a standard location or by setting the # DOTFONTPATH environment variable or by setting DOT_FONTPATH to the directory # containing the font. @@ -1478,7 +1640,7 @@ CALL_GRAPH = YES CALLER_GRAPH = YES # If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen -# will graphical hierarchy of all classes instead of a textual one. +# will generate a graphical hierarchy of all classes instead of a textual one. GRAPHICAL_HIERARCHY = YES @@ -1490,10 +1652,10 @@ GRAPHICAL_HIERARCHY = YES DIRECTORY_GRAPH = YES # The DOT_IMAGE_FORMAT tag can be used to set the image format of the images -# generated by dot. Possible values are png, jpg, or gif +# generated by dot. Possible values are svg, png, jpg, or gif. # If left blank png will be used. -DOT_IMAGE_FORMAT = gif +DOT_IMAGE_FORMAT = png # The tag DOT_PATH can be used to specify the path where the dot tool can be # found. If left blank, it is assumed the dot tool can be found in the path. @@ -1506,6 +1668,12 @@ DOT_PATH = DOTFILE_DIRS = +# The MSCFILE_DIRS tag can be used to specify one or more directories that +# contain msc files that are included in the documentation (see the +# \mscfile command). + +MSCFILE_DIRS = + # The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of # nodes that will be shown in the graph. If the number of nodes in a graph # becomes larger than this value, doxygen will truncate the graph, which is From 6c5c16d847de151a018d6cbae0fa03eb02ab5756 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 11 Jan 2012 19:50:16 +0100 Subject: [PATCH 056/112] crop image size to size of actual logo --- data/pictures/penguin_logo.svg | 66 +++++++++++++++++++--------------- 1 file changed, 37 insertions(+), 29 deletions(-) diff --git a/data/pictures/penguin_logo.svg b/data/pictures/penguin_logo.svg index 9ae8538987..8c9a98c24a 100644 --- a/data/pictures/penguin_logo.svg +++ b/data/pictures/penguin_logo.svg @@ -1,23 +1,24 @@ + + inkscape:version="0.48.2 r9819" + sodipodi:docname="penguin_logo.svg" + version="1.1"> + inkscape:window-width="1680" + inkscape:window-height="1001" + inkscape:window-x="0" + inkscape:window-y="25" + showgrid="false" + fit-margin-top="10" + fit-margin-left="10" + fit-margin-right="10" + fit-margin-bottom="10" + inkscape:window-maximized="1" /> - + - image/svg+xml + rdf:about=""> + image/svg+xml @@ -54,29 +57,34 @@ + id="layer1" + transform="translate(6.1774787,3.2309135)"> + sodipodi:nodetypes="cccccccccccccccccccccccccccc" + inkscape:connector-curvature="0" /> + sodipodi:nodetypes="ccccccccccccccccccccccccccccccccccccccccccccccccccccc" + inkscape:connector-curvature="0" /> + sodipodi:nodetypes="cccccccccccccccccccccccccccccccccccccccccccccccccccccccccc" + inkscape:connector-curvature="0" /> + sodipodi:nodetypes="ccccccccccccccccccccccccccccccccccccccccccccccccsccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccccc" + inkscape:connector-curvature="0" /> From 2c3abfa9677d76bc83a1b86bed2ed8edecc89584 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 11 Jan 2012 22:01:11 +0100 Subject: [PATCH 057/112] uncomment tunnel in lisa_m_test_progs --- conf/autopilot/lisa_m_test_progs.makefile | 34 +++++++++++------------ 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/conf/autopilot/lisa_m_test_progs.makefile b/conf/autopilot/lisa_m_test_progs.makefile index e5c334f6f0..9135a84da8 100644 --- a/conf/autopilot/lisa_m_test_progs.makefile +++ b/conf/autopilot/lisa_m_test_progs.makefile @@ -714,22 +714,22 @@ test_imu_aspirin.CFLAGS += -DUSE_DMA1_C4_IRQ # SPI2 Rx DMA #test_manual.srcs += $(SRC_SUBSYSTEMS)/radio_control.c \ # subsystems/radio_control/spektrum.c \ # $(SRC_ARCH)/subsystems/radio_control/spektrum_arch.c + + + # +# tunnel # -# -## -## tunnel -## -#tunnel.ARCHDIR = $(ARCH) -#tunnel.CFLAGS += -I$(SRC_LISA) -I$(ARCH) -DPERIPHERALS_AUTO_INIT -#tunnel.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) -#tunnel.srcs += $(SRC_AIRBORNE)/mcu.c \ -# $(SRC_ARCH)/mcu_arch.c \ -# $(SRC_LISA)/tunnel_hw.c \ -# $(SRC_ARCH)/stm32_exceptions.c \ -# $(SRC_ARCH)/stm32_vector_table.c -#tunnel.CFLAGS += -DUSE_LED -#tunnel.srcs += $(SRC_ARCH)/led_hw.c -#tunnel.CFLAGS += -DUSE_SYS_TIME -DSYS_TIME_LED=$(SYS_TIME_LED) -#tunnel.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' -#tunnel.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c +tunnel.ARCHDIR = $(ARCH) +tunnel.CFLAGS += -I$(SRC_LISA) -I$(ARCH) -DPERIPHERALS_AUTO_INIT +tunnel.CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) +tunnel.srcs += $(SRC_AIRBORNE)/mcu.c \ + $(SRC_ARCH)/mcu_arch.c \ + $(SRC_LISA)/tunnel_hw.c \ + $(SRC_ARCH)/stm32_exceptions.c \ + $(SRC_ARCH)/stm32_vector_table.c +tunnel.CFLAGS += -DUSE_LED +tunnel.srcs += $(SRC_ARCH)/led_hw.c +tunnel.CFLAGS += -DUSE_SYS_TIME -DSYS_TIME_LED=$(SYS_TIME_LED) +tunnel.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' +tunnel.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c From 37a23b194058f235a0f1c34aefa789b2c4343832 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 11 Jan 2012 22:22:29 +0100 Subject: [PATCH 058/112] added uart tunnel for lisa to setup firmware makefile --- conf/autopilot/setup.makefile | 26 +++++++++++++++++++++++++- 1 file changed, 25 insertions(+), 1 deletion(-) diff --git a/conf/autopilot/setup.makefile b/conf/autopilot/setup.makefile index f4bea44b93..ca6ac88fc1 100644 --- a/conf/autopilot/setup.makefile +++ b/conf/autopilot/setup.makefile @@ -9,15 +9,31 @@ CFG_SHARED=$(PAPARAZZI_SRC)/conf/autopilot/subsystems/shared SRC_ARCH=arch/$(ARCH) SRC_FIRMWARE=firmwares/setup +SRC_LISA=lisa SETUP_INC = -I$(SRC_FIRMWARE) $(TARGET).CFLAGS += -DBOARD_CONFIG=$(BOARD_CFG) # a test program to tunnel between both uart +ifeq ($(ARCH), lpc21) tunnel.CFLAGS += -DUSE_LED tunnel.srcs += $(SRC_ARCH)/uart_tunnel.c tunnel.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c +else ifeq ($(ARCH), stm32) +tunnel.ARCHDIR = $(ARCH) +tunnel.CFLAGS += -I$(SRC_LISA) -I$(ARCH) -DPERIPHERALS_AUTO_INIT +tunnel.srcs += mcu.c \ + $(SRC_ARCH)/mcu_arch.c \ + $(SRC_LISA)/tunnel_hw.c \ + $(SRC_ARCH)/stm32_exceptions.c \ + $(SRC_ARCH)/stm32_vector_table.c +tunnel.CFLAGS += -DUSE_LED +tunnel.srcs += $(SRC_ARCH)/led_hw.c +tunnel.CFLAGS += -DUSE_SYS_TIME -DSYS_TIME_LED=$(SYS_TIME_LED) +tunnel.CFLAGS += -DPERIODIC_TASK_PERIOD='SYS_TICS_OF_SEC(1./512.)' +tunnel.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c +endif # for the usb_tunnel we need to set PCLK higher with the flag USE_USB_HIGH_PCLK @@ -40,7 +56,11 @@ usb_tunnel_1.srcs += $(SRC_ARCH)/lpcusb/usbcontrol.c $(SRC_ARCH)/lpcusb/usbstdre usb_tunnel_1.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c usb_tunnel_1.srcs += mcu.c $(SRC_ARCH)/mcu_arch.c else -$(error usb_tunnel currently only implemented for the lpc21) +ifeq ($(TARGET),usb_tunnel_0) +$(error usb_tunnel_0 currently only implemented for the lpc21) +else ifeq ($(TARGET),usb_tunnel_1) +$(error usb_tunnel_1 currently only implemented for the lpc21) +endif endif @@ -73,9 +93,13 @@ endif # a test program to setup actuators +ifeq ($(ARCH), lpc21) setup_actuators.CFLAGS += -DFBW -DUSE_LED -DTIME_LED=1 setup_actuators.CFLAGS += -DUSE_UART1 -DUART1_BAUD=B57600 -DDOWNLINK_DEVICE=Uart1 -DPPRZ_UART=Uart1 setup_actuators.CFLAGS += -DDOWNLINK -DDOWNLINK_TRANSPORT=PprzTransport -DDATALINK=PPRZ setup_actuators.CFLAGS += -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 setup_actuators.CFLAGS += $(SETUP_INC) -Ifirmwares/fixedwing setup_actuators.srcs += sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c pprz_transport.c downlink.c $(SRC_FIRMWARE)/setup_actuators.c mcu_periph/uart.c $(SRC_ARCH)/mcu_periph/uart_arch.c firmwares/fixedwing/main.c mcu.c $(SRC_ARCH)/mcu_arch.c +else ifeq ($(TARGET),setup_actuators) +$(error setup_actuators currently only implemented for the lpc21) +endif From 8e732d0f4d54a5924752bae373f25187676d9818 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 12 Jan 2012 00:10:45 +0100 Subject: [PATCH 059/112] added mainpage for doxygen --- Doxyfile | 2 +- README | 2 -- doc/mainpage.dox | 13 +++++++++++++ 3 files changed, 14 insertions(+), 3 deletions(-) create mode 100644 doc/mainpage.dox diff --git a/Doxyfile b/Doxyfile index b8d4474f7d..d255bd3d99 100644 --- a/Doxyfile +++ b/Doxyfile @@ -609,7 +609,7 @@ WARN_LOGFILE = # directories like "/usr/src/myproject". Separate the files or directories # with spaces. -INPUT = sw/airborne +INPUT = doc/mainpage.dox sw/airborne # 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 diff --git a/README b/README index 1fbae924f2..ed5b36cc2c 100644 --- a/README +++ b/README @@ -39,8 +39,6 @@ conf: the configuration directory (airframe, radio, ... descriptions). data: where to put read-only data (e.g. maps, terrain elevation files, icons) -hw: hardware (electronic schemas, PCBs, ...) - sw: software (onboard, ground station, simulation, ...) var: products of compilation, cache for the map tiles, ... diff --git a/doc/mainpage.dox b/doc/mainpage.dox new file mode 100644 index 0000000000..26226d1f45 --- /dev/null +++ b/doc/mainpage.dox @@ -0,0 +1,13 @@ +/** +\mainpage + +\section intro Introduction + +\subsection whatis What is Paparazzi + +Paparazzi is an attempt to develop a free software Unmanned (Air) Vehicle System. + As of today the system is being used successfuly by a number of hobyists, universities and companies all over the world, on vehicle of various size ( 100g to 25Kg ) and of various nature ( fixed wing, rotorcrafts, boats and surface vehicles). + + + +*/ From 55672048f0a309749d93985f26b656ac5fd2e9de Mon Sep 17 00:00:00 2001 From: Martin Mueller Date: Sun, 15 Jan 2012 16:14:10 +0000 Subject: [PATCH 060/112] Increase PCLK to use USB mass storage with LPC --- conf/autopilot/logger.makefile | 3 +++ sw/airborne/firmwares/logger/main_logger.c | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/conf/autopilot/logger.makefile b/conf/autopilot/logger.makefile index 1845dd204b..680131df66 100644 --- a/conf/autopilot/logger.makefile +++ b/conf/autopilot/logger.makefile @@ -50,6 +50,9 @@ ap.srcs += mcu.c #set SPI interface for SD card (0 or 1) ap.CFLAGS += -DHW_ENDPOINT_LPC2000_SPINUM=$(SPI_CHANNEL) +#LPC2148 USB hw module needs at least 18MHz PCLK +ap.CFLAGS += -DUSE_USB_HIGH_PCLK + #efsl ap.CFLAGS += -I $(SRC_ARCH)/efsl/inc -I $(SRC_ARCH)/efsl/conf diff --git a/sw/airborne/firmwares/logger/main_logger.c b/sw/airborne/firmwares/logger/main_logger.c index 8f3eea1406..cc23a76b42 100644 --- a/sw/airborne/firmwares/logger/main_logger.c +++ b/sw/airborne/firmwares/logger/main_logger.c @@ -100,7 +100,7 @@ #endif #ifndef LOG_STOP_KEY -/* BUTTON that stops logging (BUTTON = P0.7, DTR = P0.13, INT1 = P0.14) */ +/* BUTTON that stops logging (PPM_IN = P0.6, BUTTON = P0.7, DTR = P0.13, INT1 = P0.14) */ #define LOG_STOP_KEY 7 #endif From bb1dcf1352078de0a877bedd1eecf28e17133f6f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 16 Jan 2012 19:04:33 +0100 Subject: [PATCH 061/112] some more doxygen comments --- sw/airborne/subsystems/ahrs.h | 66 +++++++++++++++++++++++++---------- sw/airborne/subsystems/gps.c | 5 +++ sw/airborne/subsystems/gps.h | 20 ++++++----- sw/airborne/subsystems/imu.c | 4 +++ sw/airborne/subsystems/imu.h | 34 ++++++++++-------- 5 files changed, 88 insertions(+), 41 deletions(-) diff --git a/sw/airborne/subsystems/ahrs.h b/sw/airborne/subsystems/ahrs.h index 5a30258d63..158f8a7fd8 100644 --- a/sw/airborne/subsystems/ahrs.h +++ b/sw/airborne/subsystems/ahrs.h @@ -19,6 +19,10 @@ * Boston, MA 02111-1307, USA. */ +/** \file ahrs.h + * \brief Attitude and Heading Reference System interface + */ + #ifndef AHRS_H #define AHRS_H @@ -34,41 +38,44 @@ #include AHRS_TYPE_H #endif - +/** Attitude and Heading Reference System state (fixed point version) */ struct Ahrs { - struct Int32Quat ltp_to_imu_quat; - struct Int32Eulers ltp_to_imu_euler; - struct Int32RMat ltp_to_imu_rmat; - struct Int32Rates imu_rate; + struct Int32Quat ltp_to_imu_quat; ///< Rotation from LocalTangentPlane to IMU frame as unit quaternion + struct Int32Eulers ltp_to_imu_euler; ///< Rotation from LocalTangentPlane to IMU frame as Euler angles + struct Int32RMat ltp_to_imu_rmat; ///< Rotation from LocalTangentPlane to IMU frame as Rotation Matrix + struct Int32Rates imu_rate; ///< Rotational velocity in IMU frame - struct Int32Quat ltp_to_body_quat; - struct Int32Eulers ltp_to_body_euler; - struct Int32RMat ltp_to_body_rmat; - struct Int32Rates body_rate; + struct Int32Quat ltp_to_body_quat; ///< Rotation from LocalTangentPlane to body frame as unit quaternion + struct Int32Eulers ltp_to_body_euler; ///< Rotation from LocalTangentPlane to body frame as Euler angles + struct Int32RMat ltp_to_body_rmat; ///< Rotation from LocalTangentPlane to body frame as Rotation Matrix + struct Int32Rates body_rate; ///< Rotational velocity in body frame - uint8_t status; + uint8_t status; ///< status of the AHRS, AHRS_UNINIT or AHRS_RUNNING }; +/** Attitude and Heading Reference System state (floating point version) */ struct AhrsFloat { - struct FloatQuat ltp_to_imu_quat; - struct FloatEulers ltp_to_imu_euler; - struct FloatRMat ltp_to_imu_rmat; - struct FloatRates imu_rate; + struct FloatQuat ltp_to_imu_quat; ///< Rotation from LocalTangentPlane to IMU frame as unit quaternion + struct FloatEulers ltp_to_imu_euler; ///< Rotation from LocalTangentPlane to IMU frame as Euler angles + struct FloatRMat ltp_to_imu_rmat; ///< Rotation from LocalTangentPlane to IMU frame as Rotation Matrix + struct FloatRates imu_rate; ///< Rotational velocity in IMU frame struct FloatRates imu_rate_previous; struct FloatRates imu_rate_d; - struct FloatQuat ltp_to_body_quat; - struct FloatEulers ltp_to_body_euler; - struct FloatRMat ltp_to_body_rmat; - struct FloatRates body_rate; + struct FloatQuat ltp_to_body_quat; ///< Rotation from LocalTangentPlane to body frame as unit quaternion + struct FloatEulers ltp_to_body_euler; ///< Rotation from LocalTangentPlane to body frame as Euler angles + struct FloatRMat ltp_to_body_rmat; ///< Rotation from LocalTangentPlane to body frame as Rotation Matrix + struct FloatRates body_rate; ///< Rotational velocity in body frame struct FloatRates body_rate_d; // always use status from fixed point ahrs struct for now //uint8_t status; }; +/** global AHRS state (fixed point version) */ extern struct Ahrs ahrs; +/** global AHRS state (floating point version) */ extern struct AhrsFloat ahrs_float; extern float ahrs_mag_offset; @@ -86,10 +93,33 @@ extern float ahrs_mag_offset; RATES_BFP_OF_REAL(ahrs.body_rate, ahrs_float.body_rate); \ } +/** AHRS initialization. Called at startup. + * Needs to be implemented by each AHRS algorithm. + */ extern void ahrs_init(void); + +/** Aligns the AHRS. Called after ahrs_aligner has run to set initial attitude and biases. + * Must set the ahrs status to AHRS_RUNNING. + * Needs to be implemented by each AHRS algorithm. + */ extern void ahrs_align(void); + +/** Propagation. Usually integrates the gyro rates to angles. + * Reads the global #imu data struct. + * Needs to be implemented by each AHRS algorithm. + */ extern void ahrs_propagate(void); + +/** Update AHRS state with accerleration measurements. + * Reads the global #imu data struct. + * Needs to be implemented by each AHRS algorithm. + */ extern void ahrs_update_accel(void); + +/** Update AHRS state with magnetometer measurements. + * Reads the global #imu data struct. + * Needs to be implemented by each AHRS algorithm. + */ extern void ahrs_update_mag(void); #endif /* AHRS_H */ diff --git a/sw/airborne/subsystems/gps.c b/sw/airborne/subsystems/gps.c index 4d50a634dc..0c827a85f2 100644 --- a/sw/airborne/subsystems/gps.c +++ b/sw/airborne/subsystems/gps.c @@ -19,6 +19,11 @@ * Boston, MA 02111-1307, USA. */ +/** @file gps.c + * @brief Device independent GPS code + * + */ + #include "subsystems/gps.h" #include "led.h" diff --git a/sw/airborne/subsystems/gps.h b/sw/airborne/subsystems/gps.h index 2d46b16c0d..64370bb209 100644 --- a/sw/airborne/subsystems/gps.h +++ b/sw/airborne/subsystems/gps.h @@ -20,7 +20,7 @@ */ /** @file gps.h - * @brief Device independent GPS code + * @brief Device independent GPS code (interface) * */ @@ -48,16 +48,17 @@ #define GPS_NB_CHANNELS 1 #endif -/** Space Vehicle Information */ +/** data structure for Space Vehicle Information of a single satellite */ struct SVinfo { - uint8_t svid; - uint8_t flags; - uint8_t qi; - uint8_t cno; - int8_t elev; ///< deg - int16_t azim; ///< deg + uint8_t svid; ///< Satellite ID + uint8_t flags; ///< bitfield with GPS receiver specific flags + uint8_t qi; ///< quality bitfield (GPS receiver specific) + uint8_t cno; ///< Carrier to Noise Ratio (Signal Strength) in dbHz + int8_t elev; ///< elevation in deg + int16_t azim; ///< azimuth in deg }; +/** data structure for GPS information */ struct GpsState { struct EcefCoor_i ecef_pos; ///< position in ECEF in cm struct LlaCoor_i lla_pos; ///< position in LLA (lat,lon: rad*1e7; alt: mm over ellipsoid) @@ -77,7 +78,7 @@ struct GpsState { uint32_t tow; ///< time of week in ms uint8_t nb_channels; ///< Number of scanned satellites - struct SVinfo svinfos[GPS_NB_CHANNELS]; + struct SVinfo svinfos[GPS_NB_CHANNELS]; ///< holds information from the Space Vehicles (Satellites) uint32_t last_fix_ticks; ///< cpu time in ticks at last valid fix uint16_t last_fix_time; ///< cpu time in sec at last valid fix @@ -90,6 +91,7 @@ struct GpsTimeSync { uint32_t t0; ///< for time sync: hw clock ticks when GPS message is received }; +/** global GPS state */ extern struct GpsState gps; diff --git a/sw/airborne/subsystems/imu.c b/sw/airborne/subsystems/imu.c index 515adc6b38..714ce9a049 100644 --- a/sw/airborne/subsystems/imu.c +++ b/sw/airborne/subsystems/imu.c @@ -21,6 +21,10 @@ * Boston, MA 02111-1307, USA. */ +/** \file imu.c + * \brief Inertial Measurement Unit interface + */ + #include "subsystems/imu.h" struct Imu imu; diff --git a/sw/airborne/subsystems/imu.h b/sw/airborne/subsystems/imu.h index 43bf62a56f..f2889e09bf 100644 --- a/sw/airborne/subsystems/imu.h +++ b/sw/airborne/subsystems/imu.h @@ -20,6 +20,9 @@ * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. */ +/** \file imu.h + * \brief Inertial Measurement Unit interface + */ #ifndef IMU_H #define IMU_H @@ -32,23 +35,24 @@ extern void imu_impl_init(void); extern void imu_periodic(void); +/** abstract IMU interface providing fixed point interface */ struct Imu { - struct Int32Rates gyro; - struct Int32Vect3 accel; - struct Int32Vect3 mag; - struct Int32Rates gyro_prev; - struct Int32Vect3 accel_prev; - struct Int32Rates gyro_neutral; - struct Int32Vect3 accel_neutral; - struct Int32Vect3 mag_neutral; - struct Int32Rates gyro_unscaled; - struct Int32Vect3 accel_unscaled; - struct Int32Vect3 mag_unscaled; - struct Int32Quat body_to_imu_quat; - struct Int32RMat body_to_imu_rmat; + struct Int32Rates gyro; ///< gyroscope measurements + struct Int32Vect3 accel; ///< accelerometer measurements + struct Int32Vect3 mag; ///< magnetometer measurements + struct Int32Rates gyro_prev; ///< previous gyroscope measurements + struct Int32Vect3 accel_prev; ///< previous accelerometer measurements + struct Int32Rates gyro_neutral; ///< gyroscope bias + struct Int32Vect3 accel_neutral; ///< accelerometer bias + struct Int32Vect3 mag_neutral; ///< magnetometer neutral readings (bias) + struct Int32Rates gyro_unscaled; ///< unscaled gyroscope measurements + struct Int32Vect3 accel_unscaled; ///< unscaled accelerometer measurements + struct Int32Vect3 mag_unscaled; ///< unscaled magnetometer measurements + struct Int32Quat body_to_imu_quat; ///< rotation from body to imu frame as a unit quaternion + struct Int32RMat body_to_imu_rmat; ///< rotation from body to imu frame as a rotation matrix }; -/* abstract IMU interface providing floating point interface */ +/** abstract IMU interface providing floating point interface */ struct ImuFloat { struct FloatRates gyro; struct FloatVect3 accel; @@ -61,6 +65,8 @@ struct ImuFloat { }; extern void imu_float_init(struct ImuFloat* imuf); + +/** global IMU state */ extern struct Imu imu; /* underlying hardware */ From d66599129007262b30b50e880c2ae78b4cddd78c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 16 Jan 2012 19:33:25 +0100 Subject: [PATCH 062/112] doxygen: set JAVADOC_AUTOBRIEF to yes --- Doxyfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Doxyfile b/Doxyfile index d255bd3d99..ef989c692f 100644 --- a/Doxyfile +++ b/Doxyfile @@ -150,7 +150,7 @@ SHORT_NAMES = NO # comments will behave just like regular Qt-style comments # (thus requiring an explicit @brief command for a brief description.) -JAVADOC_AUTOBRIEF = NO +JAVADOC_AUTOBRIEF = YES # If the QT_AUTOBRIEF tag is set to YES then Doxygen will # interpret the first line (until the first dot) of a Qt-style From c14a4506285e1c9f249eb98eb242bf34a0451d00 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 18 Jan 2012 15:47:08 +0100 Subject: [PATCH 063/112] whitespace cleanup and doxygen stuff --- sw/airborne/subsystems/navigation/border_line.c | 7 ++++--- sw/airborne/subsystems/navigation/border_line.h | 5 +++++ sw/airborne/subsystems/navigation/gls.c | 6 ++++-- sw/airborne/subsystems/navigation/gls.h | 9 +++++++-- 4 files changed, 20 insertions(+), 7 deletions(-) diff --git a/sw/airborne/subsystems/navigation/border_line.c b/sw/airborne/subsystems/navigation/border_line.c index 39d72d3173..5dd7d42c3c 100644 --- a/sw/airborne/subsystems/navigation/border_line.c +++ b/sw/airborne/subsystems/navigation/border_line.c @@ -26,11 +26,12 @@ //modified nav_linie by Anton Kochevar, ENAC /** - * \brief navigate along a border line (line 1-2) with turns in the same direction - * + * @file subsystems/navigation/border_line.c + * @brief navigate along a border line (line 1-2) with turns in the same direction + * * you can use this function to navigate along a border if it is essetial not to cross it * navigation is along line p1, p2 with turns in the same direction to make sure you dont cross the line - * take care youre navigation radius is not to smal in strong wind conditions! + * take care youre navigation radius is not to small in strong wind conditions! */ #include "subsystems/navigation/border_line.h" diff --git a/sw/airborne/subsystems/navigation/border_line.h b/sw/airborne/subsystems/navigation/border_line.h index e3c51c9b29..7c8094b26a 100644 --- a/sw/airborne/subsystems/navigation/border_line.h +++ b/sw/airborne/subsystems/navigation/border_line.h @@ -22,6 +22,11 @@ * */ +/** + * @file subsystems/navigation/border_line.h + * @brief navigate along a border line (line 1-2) with turns in the same direction + */ + #ifndef BORDER_LINE_H #define BORDER_LINE_H diff --git a/sw/airborne/subsystems/navigation/gls.c b/sw/airborne/subsystems/navigation/gls.c index f79d641b40..7346d60ff7 100644 --- a/sw/airborne/subsystems/navigation/gls.c +++ b/sw/airborne/subsystems/navigation/gls.c @@ -22,7 +22,9 @@ */ /** - * \brief gps landing system + * @file subsystems/navigation/gls.c + * @brief gps landing system + * * gps landing system * -automatic calculation of top of decent for const app angle * -smooth intercept posible @@ -125,7 +127,7 @@ bool_t gls(uint8_t _af, uint8_t _tod, uint8_t _td) { if (init){ #ifdef USE_AIRSPEED - v_ctl_auto_airspeed_setpoint = target_speed; // set target speed for approach + v_ctl_auto_airspeed_setpoint = target_speed; // set target speed for approach #endif init = FALSE; diff --git a/sw/airborne/subsystems/navigation/gls.h b/sw/airborne/subsystems/navigation/gls.h index b26d1d0efe..f6f7ea71b8 100644 --- a/sw/airborne/subsystems/navigation/gls.h +++ b/sw/airborne/subsystems/navigation/gls.h @@ -1,5 +1,5 @@ /* - * + * * Copyright (C) 2012, Tobias Muench * * This file is part of paparazzi. @@ -17,10 +17,15 @@ * You should have received a copy of the GNU General Public License * along with paparazzi; see the file COPYING. If not, write to * the Free Software Foundation, 59 Temple Place - Suite 330, - * Boston, MA 02111-1307, USA. + * Boston, MA 02111-1307, USA. * */ +/** + * @file subsystems/navigation/gls.h + * @brief gps landing system + */ + #ifndef NAV_GLS_H #define NAV_GLS_H From cddea3426d36519a4df46e6ced1044d6bc85da4f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Wed, 18 Jan 2012 23:52:01 +0100 Subject: [PATCH 064/112] allow definition of ADC_CHANNEL_VSUPPLY in firmware section of airframe file --- sw/airborne/boards/booz_1.0.h | 3 +++ sw/airborne/boards/hb_1.1.h | 3 +++ sw/airborne/boards/lisa_l_1.0.h | 3 +++ sw/airborne/boards/lisa_m_1.0.h | 4 +++- sw/airborne/boards/navgo_1.0.h | 3 +++ sw/airborne/boards/tiny_0.99.h | 3 +++ sw/airborne/boards/tiny_1.1.h | 3 +++ sw/airborne/boards/tiny_2.0.h | 3 +++ sw/airborne/boards/tiny_2.1.h | 3 +++ sw/airborne/boards/tiny_sim.h | 3 +++ sw/airborne/boards/umarim_1.0.h | 3 +++ 11 files changed, 33 insertions(+), 1 deletion(-) diff --git a/sw/airborne/boards/booz_1.0.h b/sw/airborne/boards/booz_1.0.h index db7e8069b6..2d6d2a5b8a 100644 --- a/sw/airborne/boards/booz_1.0.h +++ b/sw/airborne/boards/booz_1.0.h @@ -91,11 +91,14 @@ #endif /* battery */ +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank0(2) #ifndef USE_AD0 #define USE_AD0 #endif #define USE_AD0_2 +#endif #define DefaultVoltageOfAdc(adc) (0.0183*adc) diff --git a/sw/airborne/boards/hb_1.1.h b/sw/airborne/boards/hb_1.1.h index 317efcffc8..4599681f72 100644 --- a/sw/airborne/boards/hb_1.1.h +++ b/sw/airborne/boards/hb_1.1.h @@ -114,11 +114,14 @@ #define USE_AD1_4 #endif +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(6) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_6 +#endif #define DefaultVoltageOfAdc(adc) (0.032362123*adc) diff --git a/sw/airborne/boards/lisa_l_1.0.h b/sw/airborne/boards/lisa_l_1.0.h index 0923a56a40..5cf7ef8e27 100644 --- a/sw/airborne/boards/lisa_l_1.0.h +++ b/sw/airborne/boards/lisa_l_1.0.h @@ -24,7 +24,10 @@ /* PA0 - ADC0 */ +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY 2 +#endif #define DefaultVoltageOfAdc(adc) (0.0059*adc) /* Onboard ADCs */ #define BOARD_ADC_CHANNEL_1 ADC_Channel_8 diff --git a/sw/airborne/boards/lisa_m_1.0.h b/sw/airborne/boards/lisa_m_1.0.h index a9dfc3bff4..fbc668aae8 100644 --- a/sw/airborne/boards/lisa_m_1.0.h +++ b/sw/airborne/boards/lisa_m_1.0.h @@ -30,8 +30,10 @@ #define IMU_ACC_DRDY_GPIO GPIOB #define IMU_ACC_DRDY_GPIO_PORTSOURCE GPIO_PortSourceGPIOB - +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY 2 +#endif #define DefaultVoltageOfAdc(adc) (0.00485*adc) /* Onboard ADCs */ diff --git a/sw/airborne/boards/navgo_1.0.h b/sw/airborne/boards/navgo_1.0.h index da87c56b1c..17a6fbf118 100644 --- a/sw/airborne/boards/navgo_1.0.h +++ b/sw/airborne/boards/navgo_1.0.h @@ -43,11 +43,14 @@ /* ADC */ /* battery */ +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(3) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_3 +#endif #define DefaultVoltageOfAdc(adc) (0.01837*adc) diff --git a/sw/airborne/boards/tiny_0.99.h b/sw/airborne/boards/tiny_0.99.h index a2891e70f7..f618356e65 100644 --- a/sw/airborne/boards/tiny_0.99.h +++ b/sw/airborne/boards/tiny_0.99.h @@ -116,11 +116,14 @@ #define USE_AD1_2 #endif +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(6) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_6 +#endif #define DefaultVoltageOfAdc(adc) (0.01787109375*adc) diff --git a/sw/airborne/boards/tiny_1.1.h b/sw/airborne/boards/tiny_1.1.h index bec08225e0..d24360cb36 100644 --- a/sw/airborne/boards/tiny_1.1.h +++ b/sw/airborne/boards/tiny_1.1.h @@ -124,11 +124,14 @@ #define USE_AD1_5 #endif +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(6) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_6 +#endif #define DefaultVoltageOfAdc(adc) (0.01787109375*adc) diff --git a/sw/airborne/boards/tiny_2.0.h b/sw/airborne/boards/tiny_2.0.h index 23bc02f777..1e2c48ead0 100644 --- a/sw/airborne/boards/tiny_2.0.h +++ b/sw/airborne/boards/tiny_2.0.h @@ -122,11 +122,14 @@ #define USE_AD1_3 #endif +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(5) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_5 +#endif #ifndef VoltageOfAdc diff --git a/sw/airborne/boards/tiny_2.1.h b/sw/airborne/boards/tiny_2.1.h index 772834da7c..d80dad8efa 100644 --- a/sw/airborne/boards/tiny_2.1.h +++ b/sw/airborne/boards/tiny_2.1.h @@ -148,11 +148,14 @@ #define USE_AD1_3 #endif +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(5) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_5 +#endif #define DefaultVoltageOfAdc(adc) (0.01787109375*adc) diff --git a/sw/airborne/boards/tiny_sim.h b/sw/airborne/boards/tiny_sim.h index ff3845ca86..0c6fc3da1c 100644 --- a/sw/airborne/boards/tiny_sim.h +++ b/sw/airborne/boards/tiny_sim.h @@ -122,11 +122,14 @@ #endif /* #define ADC_3 AdcBank1(7) Used for VSUPPLY */ +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank1(7) #ifndef USE_AD1 #define USE_AD1 #endif #define USE_AD1_7 +#endif #define DefaultVoltageOfAdc(adc) (0.01787109375*adc) diff --git a/sw/airborne/boards/umarim_1.0.h b/sw/airborne/boards/umarim_1.0.h index f4c87cbb96..eb47a0545c 100644 --- a/sw/airborne/boards/umarim_1.0.h +++ b/sw/airborne/boards/umarim_1.0.h @@ -78,11 +78,14 @@ /* battery */ +/* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ +#ifndef ADC_CHANNEL_VSUPPLY #define ADC_CHANNEL_VSUPPLY AdcBank0(2) #ifndef USE_AD0 #define USE_AD0 #endif #define USE_AD0_2 +#endif #define DefaultVoltageOfAdc(adc) (0.0247*adc) From 187941d420d9538b247802820c468605a2ff00ba Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 19 Jan 2012 13:41:49 +0100 Subject: [PATCH 065/112] added dir for dev manual and style guide. github pages repo now under doc/html --- .gitignore | 2 +- Doxyfile | 4 +- doc/mainpage.dox | 13 --- doc/manual/mainpage.dox | 29 ++++++ doc/manual/style.dox | 223 ++++++++++++++++++++++++++++++++++++++++ 5 files changed, 255 insertions(+), 16 deletions(-) delete mode 100644 doc/mainpage.dox create mode 100644 doc/manual/mainpage.dox create mode 100644 doc/manual/style.dox diff --git a/.gitignore b/.gitignore index b16f9b2ad5..c6fef4c208 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,5 @@ # ignore html dir for github pages -/html +/doc/html *.so *.[oa] diff --git a/Doxyfile b/Doxyfile index ef989c692f..51dd13e986 100644 --- a/Doxyfile +++ b/Doxyfile @@ -51,7 +51,7 @@ PROJECT_LOGO = data/pictures/penguin_icon.png # If a relative path is entered, it will be relative to the location # where doxygen was started. If left blank the current directory will be used. -OUTPUT_DIRECTORY = html +OUTPUT_DIRECTORY = doc/html # If the CREATE_SUBDIRS tag is set to YES, then doxygen will create # 4096 sub-directories (in 2 levels) under the output directory of each output @@ -609,7 +609,7 @@ WARN_LOGFILE = # directories like "/usr/src/myproject". Separate the files or directories # with spaces. -INPUT = doc/mainpage.dox sw/airborne +INPUT = doc/manual sw/airborne # 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 diff --git a/doc/mainpage.dox b/doc/mainpage.dox deleted file mode 100644 index 26226d1f45..0000000000 --- a/doc/mainpage.dox +++ /dev/null @@ -1,13 +0,0 @@ -/** -\mainpage - -\section intro Introduction - -\subsection whatis What is Paparazzi - -Paparazzi is an attempt to develop a free software Unmanned (Air) Vehicle System. - As of today the system is being used successfuly by a number of hobyists, universities and companies all over the world, on vehicle of various size ( 100g to 25Kg ) and of various nature ( fixed wing, rotorcrafts, boats and surface vehicles). - - - -*/ diff --git a/doc/manual/mainpage.dox b/doc/manual/mainpage.dox new file mode 100644 index 0000000000..45c4e60b25 --- /dev/null +++ b/doc/manual/mainpage.dox @@ -0,0 +1,29 @@ +/** @mainpage Paparazzi Developer's Guide + +Welcome to the Paparazzi Developer's Guide -- the developer's resource for +learning about the internal architecture of the Paparazzi project. @par + +Developers that want to contribute to Paparazzi should read the following +sections before starting work: + +- The @subpage styleguide provides rules that developers should + follow when writing new code for Paparazzi. + +@ref primer provide introductory materials for new developers on various +specific topics. + + + */ + +/** @page primer Paparazzi Technical Primers + +This pages lists Technical Primers available for Paparazzi Developers. +They seek to provide information to pull novices up the learning curves +associated with the fundamental technologies used by Paparazzi. + +- TODO + + +Contributions or suggestions for new Technical Primers are welcome. + + */ diff --git a/doc/manual/style.dox b/doc/manual/style.dox new file mode 100644 index 0000000000..c59be63807 --- /dev/null +++ b/doc/manual/style.dox @@ -0,0 +1,223 @@ +/** @page styleguide Style Guides + +The goals for each of these guides are: +- to produce correct code that appears clean, consistent, and readable, +- to allow developers to create patches that conform to a standard, and +- to eliminate these issues as points of future contention. + +Some of these rules may be ignored in the spirit of these stated goals; +however, such exceptions should be fairly rare. + +The following style guides describe a formatting, naming, and other +conventions that should be followed when writing or changing the Papaprazzi +code or documentation: + +- @subpage stylec +- @subpage styledoxygen + + +Feedback would be welcome to improve the Paparazzi guidelines. + */ + +/** @page stylec C Style Guide + +This page contains guidelines for writing new C source code for the +OpenOCD project. + +@section styleformat Formatting Guide + +- remove any trailing white space at the end of lines. +- use 2 spaces for indentation; do NOT use tabs. +- use Unix line endings ('\\n'); do NOT use DOS endings ('\\r\\n') +- limit adjacent empty lines to at most two (2). +- remove any trailing empty lines at the end of source files +- do not "comment out" code from the tree; instead, one should either: + -# remove it entirely (git can retrieve the old version), or + -# use an @c \#if/\#endif block. + +@section stylenames Naming Rules + +- most identifiers must use lower-case letters (and digits) only. + - macros should use upper-case letters (and digits) only. + +@section styletypes Type Guidelines +- use the types from \: + - @c int8_t, @c int16_t, @c int32_t, or @c int64_t: signed types of specified size + - @c uint8_t, @c uint16_t, @c uint32_t, or @c uint64_t: unsigned types of specified size + +@section stylefunc Functions + +- static inline functions should be prefered over macros in most cases: +@code +/* do NOT define macro-like functions like this... */ +#define CUBE(x) ((x) * (x) * (x)) +/* instead, define the same expression using a C99 inline function */ +static inline int cube(int x) { return x * x * x; } +@endcode +- Functions should be declared static unless required by other modules + - define static functions before first usage to avoid forward declarations. +- Functions should have no space between its name and its parameter list: +@code +int32_t f(int32_t x1, int32_t x2) +{ + ... + int32_t y = f(x1, x2 - x1); + ... +} +@endcode + +@section stylecpp Preprocessor directives +- For conditional compilation use @c #if instead of @c #ifdef. +Someone might write code like: +@code +#ifdef USE_FOO + bar(); +#endif +@endcode +Someone else might compile the code with turned-off foo info like: +@verbatim + gcc stuff.c -DUSE_FOO=0 +@endverbatim +So use @c #if not @c #ifdef to turn a feature on or off. This works fine, and does the right thing, even if USE_FOO is not defined at all (!) +@code +#if USE_FOO + bar(); +#endif +@endcode +- If you really need to test whether a symbol is defined or not, test it with the @c defined construct. + + */ + +/** @page styledoxygen Doxygen Style Guide + +The following sections provide guidelines for OpenOCD developers +who wish to write Doxygen comments in the code or this manual. +For an introduction to Doxygen documentation, +see the @ref primerdoxygen. + +@section styledoxyblocks Doxygen Block Selection + +Several different types of Doxygen comments can be used; often, +one style will be the most appropriate for a specific context. +The following guidelines provide developers with heuristics for +selecting an appropriate form and writing consistent documentation +comments. + +-# use @c /// to for one-line documentation of instances. +-# for documentation requiring multiple lines, use a "block" style: +@verbatim +/** + * @brief First sentence is short description. Remaining text becomes + * the full description block, where "empty" lines start new paragraphs. + * + * One can make text appear in @a italics, @b bold, @c monospace, or + * in blocks such as the one in which this example appears in the Style + * Guide. See the Doxygen Manual for the full list of commands. + * + * @param foo For a function, describe the parameters (e.g. @a foo). + * @returns The value(s) returned, or possible error conditions. + */ +@endverbatim + -# The block should start on the line following the opening @c /**. + -# The end of the block, \f$*/\f$, should also be on its own line. + -# Every line in the block should have a @c '*' in-line with its start: + - A leading space is required to align the @c '*' with the @c /** line. + - A single "empty" line should separate the function documentation + from the block of parameter and return value descriptions. + - Except to separate paragraphs of documentation, other extra + "empty" lines should be removed from the block. + -# Only single spaces should be used; do @b not add mid-line indentation. +-# If the total line length will be less than 80 columns, then + - The /**< description form can be used on the same line for a detailed description. + - The ///< brief form can be used for brief descriptions. + - This style should be used sparingly; the best use is for fields: +@verbatim +int field; /**< detailed field description */ +int field2; ///< a brief description +@endverbatim +-# Every documented file should contain a block with @c \@file after the license header: +@verbatim +/** + * @file foo/bar/file.c + * @brief Brief description of file. + * + * More detailed description of file. + */ +@endverbatim + +@section styledoxyall Doxygen Style Guide + +The following guidelines apply to all Doxygen comment blocks: + +-# Use the @c '\@cmd' form for all doxygen commands (do @b not use @c '\\cmd'). +-# Use symbol names such that Doxygen automatically creates links: + -# @c function_name() can be used to reference functions + (e.g. ahrs_propagate()). + -# @c struct_name::member_name should be used to reference structure + fields in the documentation (e.g. @c Ahrs::body_rate). + -# URLS get converted to markup automatically, without any extra effort. + -# new pages can be linked into the heirarchy by using the @c \@subpage + command somewhere the page(s) under which they should be linked: + -# use @c \@ref in other contexts to create links to pages and sections. +-# Use good Doxygen mark-up: + -# '\@a' (italics) should be used to reference parameters (e.g. foo). + -# '\@b' (bold) should be used to emphasizing single words. + -# '\@c' (monospace) should be used with file names and + code symbols, so they appear visually distinct from + surrounding text. + -# To mark-up multiple words, the HTML alternatives must be used. +-# Two spaces should be used when nesting lists; do @b not use '\\t' in lists. +-# Code examples provided in documentation must conform to the Style Guide. + +@section styledoxytext Doxygen Text Inputs + +In addition to the guidelines in the preceding sections, the following +additional style guidelines should be considered when writing +documentation as part of standalone text files: + +-# Text files must contain Doxygen at least one comment block: + -# Documentation should begin in the first column (except for nested lists). + -# Do NOT use the @c '*' convention that must be used in the source code. +-# Each file should contain at least one @c \@page block. + -# Each new page should be listed as a \@subpage in the \@page block + of the page that should serve as its parent. + -# Large pages should be structure in parts using meaningful \@section + and \@subsection commands. +-# Include a @c \@file block at the end of each Doxygen @c .dox file to + document its contents: + - Doxygen creates such pages for files automatically, but no content + will appear on them for those that only contain manual pages. + - The \@file block should provide useful meta-documentation to assist + techincal writers; typically, a list of the pages that it contains. + - For example, the @ref styleguide exists in @c doc/manual/style.dox, + which contains a reference back to itself. +-# The \@file and \@page commands should begin on the same line as + the start of the Doxygen comment: +@verbatim +/** @page pagename Page Title + +Documentation for the page. + + */ +/** @file + +This file contains the @ref pagename page. + + */ +@endverbatim + +For an example, the Doxygen source for this Style Guide can be found in +@c doc/manual/style.dox, alongside other parts of The Manual. + + */ + +/** @file + +This file contains the @ref styleguide pages. The @ref styleguide pages +include the following Style Guides for their respective code and +documentation languages: + +- @ref stylec +- @ref styledoxygen + + */ From 7e6b75beade683e8d1280e1f59f2a31e13eb1f73 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 19 Jan 2012 13:42:14 +0100 Subject: [PATCH 066/112] typo in comments --- sw/airborne/led.h | 2 +- sw/airborne/mcu.h | 2 +- sw/airborne/mcu_periph/adc.h | 2 +- sw/airborne/mcu_periph/spi.h | 2 +- sw/airborne/mcu_periph/uart.h | 2 +- sw/airborne/mcu_periph/usb_serial.h | 2 +- sw/airborne/sys_time.h | 2 +- 7 files changed, 7 insertions(+), 7 deletions(-) diff --git a/sw/airborne/led.h b/sw/airborne/led.h index 55a9c0493e..802056f216 100644 --- a/sw/airborne/led.h +++ b/sw/airborne/led.h @@ -23,7 +23,7 @@ */ /** \file led.h - * \brief arch independant LED (Light Emitting Diodes) API + * \brief arch independent LED (Light Emitting Diodes) API * * */ diff --git a/sw/airborne/mcu.h b/sw/airborne/mcu.h index 0372433374..e4fdaf5aee 100644 --- a/sw/airborne/mcu.h +++ b/sw/airborne/mcu.h @@ -23,7 +23,7 @@ */ /** \file mcu.h - * \brief arch independant mcu ( Micro Controller Unit ) utilities + * \brief arch independent mcu ( Micro Controller Unit ) utilities */ #ifndef MCU_H diff --git a/sw/airborne/mcu_periph/adc.h b/sw/airborne/mcu_periph/adc.h index bb2f9362c2..feb7cf4c47 100644 --- a/sw/airborne/mcu_periph/adc.h +++ b/sw/airborne/mcu_periph/adc.h @@ -23,7 +23,7 @@ */ /** \file adc.h - * \brief arch independant ADC (Analog to Digital Converter) API + * \brief arch independent ADC (Analog to Digital Converter) API * * Facility to store last values in a circular buffer for a specific * channel: diff --git a/sw/airborne/mcu_periph/spi.h b/sw/airborne/mcu_periph/spi.h index 9cdd614a4b..c2fbf7c0c6 100644 --- a/sw/airborne/mcu_periph/spi.h +++ b/sw/airborne/mcu_periph/spi.h @@ -23,7 +23,7 @@ */ /** \file mcu_periph/spi.h - * \brief arch independant SPI (Serial Peripheral Interface) API */ + * \brief arch independent SPI (Serial Peripheral Interface) API */ #ifndef SPI_H diff --git a/sw/airborne/mcu_periph/uart.h b/sw/airborne/mcu_periph/uart.h index d9ebf3b32b..d2bd283d7e 100644 --- a/sw/airborne/mcu_periph/uart.h +++ b/sw/airborne/mcu_periph/uart.h @@ -23,7 +23,7 @@ */ /** \file mcu_periph/uart.h - * \brief arch independant UART (Universal Asynchronous Receiver/Transmitter) API + * \brief arch independent UART (Universal Asynchronous Receiver/Transmitter) API * */ diff --git a/sw/airborne/mcu_periph/usb_serial.h b/sw/airborne/mcu_periph/usb_serial.h index fa080e407e..0ce1a825d1 100644 --- a/sw/airborne/mcu_periph/usb_serial.h +++ b/sw/airborne/mcu_periph/usb_serial.h @@ -23,7 +23,7 @@ */ /** \file usb_serial.h - * \brief arch independant USB API + * \brief arch independent USB API * */ diff --git a/sw/airborne/sys_time.h b/sw/airborne/sys_time.h index a665e88c5c..0c9298d433 100644 --- a/sw/airborne/sys_time.h +++ b/sw/airborne/sys_time.h @@ -23,7 +23,7 @@ */ /* - *\brief architecture independant timing functions + *\brief architecture independent timing functions * */ From fb52967c1edb24957f579b8458f430076dd8060e Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Thu, 19 Jan 2012 18:54:05 +0100 Subject: [PATCH 067/112] minor doxygen updates --- Doxyfile | 6 +++--- doc/manual/style.dox | 6 ++++-- 2 files changed, 7 insertions(+), 5 deletions(-) diff --git a/Doxyfile b/Doxyfile index 51dd13e986..bd783c89f6 100644 --- a/Doxyfile +++ b/Doxyfile @@ -25,19 +25,19 @@ DOXYFILE_ENCODING = UTF-8 # The PROJECT_NAME tag is a single word (or a sequence of words surrounded # by quotes) that should identify the project. -PROJECT_NAME = "Paparazzi UAV" +PROJECT_NAME = "Paparazzi UAS" # The PROJECT_NUMBER tag can be used to enter a project or revision number. # This could be handy for archiving the generated documentation or # if some version control system is used. -PROJECT_NUMBER = 3.5 +PROJECT_NUMBER = # Using the PROJECT_BRIEF tag one can provide an optional one line description # for a project that appears at the top of each page and should give viewer # a quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = "Paparazzi is a free software Unmanned (Air) Vehicle System." +PROJECT_BRIEF = "Paparazzi is a free software Unmanned Aircraft System." # With the PROJECT_LOGO tag one can specify an logo or icon that is # included in the documentation. The maximum height of the logo should not diff --git a/doc/manual/style.dox b/doc/manual/style.dox index c59be63807..acf471ac6b 100644 --- a/doc/manual/style.dox +++ b/doc/manual/style.dox @@ -107,7 +107,7 @@ comments. -# for documentation requiring multiple lines, use a "block" style: @verbatim /** - * @brief First sentence is short description. Remaining text becomes + * First sentence is brief description. Remaining text becomes * the full description block, where "empty" lines start new paragraphs. * * One can make text appear in @a italics, @b bold, @c monospace, or @@ -139,7 +139,7 @@ int field2; ///< a brief description @verbatim /** * @file foo/bar/file.c - * @brief Brief description of file. + * Brief description of file. * * More detailed description of file. */ @@ -150,6 +150,8 @@ int field2; ///< a brief description The following guidelines apply to all Doxygen comment blocks: -# Use the @c '\@cmd' form for all doxygen commands (do @b not use @c '\\cmd'). +-# It is not necessary to use @c \@brief since @c JAVADOC_AUTOBRIEF is enabled. + - The first line (until the first dot) is automatically treated as brief description. -# Use symbol names such that Doxygen automatically creates links: -# @c function_name() can be used to reference functions (e.g. ahrs_propagate()). From 5b44c343cf2f8c8e3b768074d2ab2fdfec2a9de3 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 21 Jan 2012 22:12:08 +0100 Subject: [PATCH 068/112] abort compilation with an error if trying to use imu_analog subsystem on stm32 --- conf/autopilot/subsystems/fixedwing/imu_analog.makefile | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/conf/autopilot/subsystems/fixedwing/imu_analog.makefile b/conf/autopilot/subsystems/fixedwing/imu_analog.makefile index 9cfc7e1d90..b91187fe7a 100644 --- a/conf/autopilot/subsystems/fixedwing/imu_analog.makefile +++ b/conf/autopilot/subsystems/fixedwing/imu_analog.makefile @@ -58,6 +58,10 @@ imu_CFLAGS += -DADC_CHANNEL_ACCEL_X=$(ACCEL_X) -DADC_CHANNEL_ACCEL_Y=$(ACCEL_Y) imu_srcs += $(SRC_SUBSYSTEMS)/imu.c imu_srcs += $(SRC_SUBSYSTEMS)/imu/imu_analog.c +else ifeq ($(ARCH), stm32) + +$(error Not implemented for the stm32 yet... should be trivial, just do it...) + endif # Keep CFLAGS/Srcs for imu in separate expression so we can assign it to other targets From 0ed489b9d13c4476517d632660db4e31e1b6e92b Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 24 Jan 2012 23:12:07 +0100 Subject: [PATCH 069/112] added eclipse project files to .gitignore --- .gitignore | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/.gitignore b/.gitignore index c6fef4c208..78379d4bf0 100644 --- a/.gitignore +++ b/.gitignore @@ -20,6 +20,13 @@ *.aux +# Eclipse IDE project files +*.cproject +*.project +*.externalToolBuilders +/build.properties +/META-INF + # Debian related files *.deb *.dsc From f20a07e3921bbd80f4cb96e64bd12e7f7b095456 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 31 Jan 2012 00:36:54 +0100 Subject: [PATCH 070/112] moved imu_analog subsystem to shared so it can be used for rotorcrafts as well --- .../subsystems/{fixedwing => shared}/imu_analog.makefile | 0 1 file changed, 0 insertions(+), 0 deletions(-) rename conf/autopilot/subsystems/{fixedwing => shared}/imu_analog.makefile (100%) diff --git a/conf/autopilot/subsystems/fixedwing/imu_analog.makefile b/conf/autopilot/subsystems/shared/imu_analog.makefile similarity index 100% rename from conf/autopilot/subsystems/fixedwing/imu_analog.makefile rename to conf/autopilot/subsystems/shared/imu_analog.makefile From 22c2440b2dd81d33149bd8f1cf7bdd1b90071446 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 6 Feb 2012 01:35:26 +0100 Subject: [PATCH 071/112] increase adxl345 range from +-2g to +-16g for aspirin driver - as the full resolution bit is set the LSB/g sensitivity stays the same - this changes the output resolution from 10 to 13 bit --- sw/airborne/subsystems/imu/imu_aspirin.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/airborne/subsystems/imu/imu_aspirin.c b/sw/airborne/subsystems/imu/imu_aspirin.c index bd207dadd8..70d4bce7b1 100644 --- a/sw/airborne/subsystems/imu/imu_aspirin.c +++ b/sw/airborne/subsystems/imu/imu_aspirin.c @@ -98,8 +98,8 @@ static void configure_accel(void) { adxl345_write_to_reg(ADXL345_REG_POWER_CTL, 1<<3); /* enable data ready interrupt */ adxl345_write_to_reg(ADXL345_REG_INT_ENABLE, 1<<7); - /* Enable full res and interrupt active low */ - adxl345_write_to_reg(ADXL345_REG_DATA_FORMAT, 1<<3|1<<5); + /* Enable full res with +-16g range and interrupt active low */ + adxl345_write_to_reg(ADXL345_REG_DATA_FORMAT, 1<<0|1<<1|1<<3|1<<5); /* clear spi rx reg to make DMA happy */ adxl345_clear_rx_buf(); /* reads data once to bring interrupt line up */ From 43a95506dcea5e1f89a52223b751e088e0b1c2d2 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 6 Feb 2012 16:31:58 +0100 Subject: [PATCH 072/112] manual: mention Paparazzi project --- doc/manual/style.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/manual/style.dox b/doc/manual/style.dox index acf471ac6b..9ae3a07c4b 100644 --- a/doc/manual/style.dox +++ b/doc/manual/style.dox @@ -22,7 +22,7 @@ Feedback would be welcome to improve the Paparazzi guidelines. /** @page stylec C Style Guide This page contains guidelines for writing new C source code for the -OpenOCD project. +Paparazzi project. @section styleformat Formatting Guide From 52953c941753713b60293616b579ab83c46d212c Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 6 Feb 2012 19:17:50 +0100 Subject: [PATCH 073/112] manual: mention Paparazzi project --- doc/manual/style.dox | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/doc/manual/style.dox b/doc/manual/style.dox index 9ae3a07c4b..c0981cfb7f 100644 --- a/doc/manual/style.dox +++ b/doc/manual/style.dox @@ -90,7 +90,7 @@ So use @c #if not @c #ifdef to turn a feature on or off. This works fine, and do /** @page styledoxygen Doxygen Style Guide -The following sections provide guidelines for OpenOCD developers +The following sections provide guidelines for Paparazzi developers who wish to write Doxygen comments in the code or this manual. For an introduction to Doxygen documentation, see the @ref primerdoxygen. From 88fa81dd185ca6afa28b4850c8e7b53a38d03150 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Wed, 8 Feb 2012 15:32:12 +0100 Subject: [PATCH 074/112] parse gps pacc in GPS_INT message --- sw/ground_segment/tmtc/rotorcraft_server.ml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/ground_segment/tmtc/rotorcraft_server.ml b/sw/ground_segment/tmtc/rotorcraft_server.ml index ac75d3e04c..2bb2ac4417 100644 --- a/sw/ground_segment/tmtc/rotorcraft_server.ml +++ b/sw/ground_segment/tmtc/rotorcraft_server.ml @@ -179,6 +179,8 @@ let log_and_parse = fun ac_name (a:Aircraft.aircraft) msg values -> a.flight_time <- ivalue "flight_time"; (*if a.gspeed > 3. && a.ap_mode = _AUTO2 then Wind.update ac_name a.gspeed a.course*) + | "GPS_INT" -> + a.gps_Pacc <- ivalue "pacc" | "ROTORCRAFT_STATUS" -> a.vehicle_type <- Rotorcraft; a.fbw.rc_status <- get_rc_status (ivalue "rc_status"); From 1f9a8bd4998951cc311a67584e9fa657aa4f246f Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Wed, 8 Feb 2012 17:30:53 +0100 Subject: [PATCH 075/112] parse tow in GPS_INT as well --- sw/ground_segment/tmtc/rotorcraft_server.ml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/ground_segment/tmtc/rotorcraft_server.ml b/sw/ground_segment/tmtc/rotorcraft_server.ml index 2bb2ac4417..a2bae0e44f 100644 --- a/sw/ground_segment/tmtc/rotorcraft_server.ml +++ b/sw/ground_segment/tmtc/rotorcraft_server.ml @@ -174,12 +174,12 @@ let log_and_parse = fun ac_name (a:Aircraft.aircraft) msg values -> a.roll <- foi32value "phi" /. angle_frac; a.pitch <- foi32value "theta" /. angle_frac; a.throttle <- foi32value "thrust" /. 2.; (* thrust / 200 * 100 *) - (*a.unix_time <- LL.unix_time_of_tow (truncate (fvalue "itow" /. 1000.)); - a.itow <- Int32.of_float (fvalue "itow");*) a.flight_time <- ivalue "flight_time"; (*if a.gspeed > 3. && a.ap_mode = _AUTO2 then Wind.update ac_name a.gspeed a.course*) | "GPS_INT" -> + a.unix_time <- LL.unix_time_of_tow (truncate (fvalue "tow" /. 1000.)); + a.itow <- Int32.of_float (fvalue "tow"); a.gps_Pacc <- ivalue "pacc" | "ROTORCRAFT_STATUS" -> a.vehicle_type <- Rotorcraft; From d86b7b91f1a4509334b01946ca7728ae758718c6 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 10 Feb 2012 16:05:35 +0100 Subject: [PATCH 076/112] baro_board module for lisa/l: USE_I2C2 --- conf/modules/baro_board.xml | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/conf/modules/baro_board.xml b/conf/modules/baro_board.xml index 020bd730e5..0553718835 100644 --- a/conf/modules/baro_board.xml +++ b/conf/modules/baro_board.xml @@ -13,13 +13,15 @@ ifeq ($(BOARD), navgo) -ap.CFLAGS += -DUSE_I2C1 -DUSE_ADS1114_1 -ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 -ap.srcs += peripherals/ads1114.c + ap.CFLAGS += -DUSE_I2C1 -DUSE_ADS1114_1 + ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 + ap.srcs += peripherals/ads1114.c else ifeq ($(BOARD), umarim) -ap.CFLAGS += -DUSE_I2C1 -DUSE_ADS1114_1 -ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 -ap.srcs += peripherals/ads1114.c + ap.CFLAGS += -DUSE_I2C1 -DUSE_ADS1114_1 + ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 + ap.srcs += peripherals/ads1114.c +else ifeq ($(BOARD), lisa_l) + ap.CFLAGS += -DUSE_I2C2 endif From 2e9faab0a7127e44a603b74cfa5292765c49ae66 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 10 Feb 2012 16:23:22 +0100 Subject: [PATCH 077/112] added a default case for switch in dc_send_command, thx Antoine --- sw/airborne/modules/digital_cam/servo_cam_ctrl.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/sw/airborne/modules/digital_cam/servo_cam_ctrl.h b/sw/airborne/modules/digital_cam/servo_cam_ctrl.h index abdc372f1f..fdd0820b4f 100644 --- a/sw/airborne/modules/digital_cam/servo_cam_ctrl.h +++ b/sw/airborne/modules/digital_cam/servo_cam_ctrl.h @@ -99,6 +99,8 @@ static inline void dc_send_command(uint8_t cmd) DC_PUSH(DC_POWER_SERVO); break; #endif + default: + break; } } From f25e5df0940d641f6083006626c58a9b6088f490 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sat, 11 Feb 2012 02:21:38 +0100 Subject: [PATCH 078/112] wrap some includes and functions for nps in #if USE_NPS --- sw/airborne/arch/sim/subsystems/imu/imu_aspirin_arch.c | 2 ++ sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c | 2 +- sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h | 2 +- sw/airborne/arch/sim/subsystems/imu/imu_crista_arch.c | 3 ++- sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c | 6 +++--- sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h | 2 +- 6 files changed, 10 insertions(+), 7 deletions(-) diff --git a/sw/airborne/arch/sim/subsystems/imu/imu_aspirin_arch.c b/sw/airborne/arch/sim/subsystems/imu/imu_aspirin_arch.c index 383dd78880..7b334860ec 100644 --- a/sw/airborne/arch/sim/subsystems/imu/imu_aspirin_arch.c +++ b/sw/airborne/arch/sim/subsystems/imu/imu_aspirin_arch.c @@ -33,6 +33,7 @@ void imu_periodic(void) { } +#if USE_NPS #include "nps_sensors.h" void imu_feed_gyro_accel(void) { @@ -56,3 +57,4 @@ void imu_feed_mag(void) { hmc5843.data.value[IMU_MAG_Z_CHAN] = sensors.mag.value.z; hmc5843.data_available = TRUE; } +#endif diff --git a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c index e680ebc675..deb32021cb 100644 --- a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c +++ b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.c @@ -35,7 +35,7 @@ void imu_periodic(void) { } -#ifdef USE_NPS +#if USE_NPS #include "nps_sensors.h" void imu_feed_gyro_accel(void) { diff --git a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h index 025acd33bf..2944460181 100644 --- a/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h +++ b/sw/airborne/arch/sim/subsystems/imu/imu_b2_arch.h @@ -31,7 +31,7 @@ extern int imu_overrun; -#ifdef USE_NPS +#if USE_NPS extern void imu_feed_gyro_accel(void); extern void imu_feed_mag(void); #endif diff --git a/sw/airborne/arch/sim/subsystems/imu/imu_crista_arch.c b/sw/airborne/arch/sim/subsystems/imu/imu_crista_arch.c index ee07d78462..4d78cef36a 100644 --- a/sw/airborne/arch/sim/subsystems/imu/imu_crista_arch.c +++ b/sw/airborne/arch/sim/subsystems/imu/imu_crista_arch.c @@ -10,7 +10,7 @@ void imu_crista_arch_init(void) { } - +#if USE_NPS #include "nps_sensors.h" void imu_feed_gyro_accel(void) { @@ -29,3 +29,4 @@ void imu_feed_mag(void) { ami601_values[IMU_MAG_Z_CHAN] = sensors.mag.value.z; ami601_status = AMI601_DATA_AVAILABLE; } +#endif diff --git a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c index be462fc82b..164a296e45 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c +++ b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.c @@ -28,7 +28,7 @@ #include #include -#ifdef USE_NPS +#if USE_NPS #include "nps_radio_control.h" #endif @@ -55,7 +55,7 @@ value send_ppm(value unit) { return unit; } -#ifdef USE_NPS +#if USE_NPS #define PPM_OF_NPS(_nps, _neutral, _min, _max) \ ((_nps) >= 0 ? (_neutral) + (_nps) * ((_max)-(_neutral)) : (_neutral) + (_nps) * ((_neutral)- (_min))) @@ -94,7 +94,7 @@ value send_ppm(value unit) { return unit; } -#ifdef USE_NPS +#if USE_NPS void radio_control_feed(void) {} #endif diff --git a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h index c0f27a3b5e..5a6bcbe639 100644 --- a/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h +++ b/sw/airborne/arch/sim/subsystems/radio_control/ppm_arch.h @@ -36,7 +36,7 @@ #define PPM_NB_CHANNEL RADIO_CONTROL_NB_CHANNEL -#ifdef USE_NPS +#if USE_NPS extern void radio_control_feed(void); #endif From 88467a5b8b4db7ce2ab9b78bada81fe826432b9c Mon Sep 17 00:00:00 2001 From: Bernard Davison Date: Sat, 11 Feb 2012 14:41:37 +1100 Subject: [PATCH 079/112] Adding place holders for test hardware configs. --- conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml | 0 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml | 0 conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml | 0 conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml | 0 conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml | 0 conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml | 0 conf/airframes/TestHardware/Tiny_2.11_fw.xml | 0 7 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml create mode 100644 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml create mode 100644 conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml create mode 100644 conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml create mode 100644 conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml create mode 100644 conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml create mode 100644 conf/airframes/TestHardware/Tiny_2.11_fw.xml diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml b/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml b/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml new file mode 100644 index 0000000000..e69de29bb2 diff --git a/conf/airframes/TestHardware/Tiny_2.11_fw.xml b/conf/airframes/TestHardware/Tiny_2.11_fw.xml new file mode 100644 index 0000000000..e69de29bb2 From 85d7eb9398ba6d7435363f4863ce54f1ec2b6773 Mon Sep 17 00:00:00 2001 From: Bernard Davison Date: Sat, 11 Feb 2012 15:55:32 +1100 Subject: [PATCH 080/112] Some very basic content for the airframe test hardware configs. --- conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml | 0 .../airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_fw.xml | 2 ++ .../airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_rc.xml | 2 ++ conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml | 0 conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml | 2 ++ conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml | 2 ++ conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml | 2 ++ conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml | 2 ++ conf/airframes/TestHardware/Tiny_2.11_fw.xml | 2 ++ 9 files changed, 14 insertions(+) delete mode 100644 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml create mode 100644 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_fw.xml create mode 100644 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_rc.xml delete mode 100644 conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_fw.xml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_fw.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_fw.xml new file mode 100644 index 0000000000..ab07cfb2b8 --- /dev/null +++ b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_fw.xml @@ -0,0 +1,2 @@ + + diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_rc.xml new file mode 100644 index 0000000000..ab07cfb2b8 --- /dev/null +++ b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_overo_rc.xml @@ -0,0 +1,2 @@ + + diff --git a/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_aspirin_v1.5_rc.xml deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml index e69de29bb2..ab07cfb2b8 100644 --- a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml +++ b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_fw.xml @@ -0,0 +1,2 @@ + + diff --git a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml index e69de29bb2..ab07cfb2b8 100644 --- a/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml +++ b/conf/airframes/TestHardware/LisaL_v1.1_b2_v1.2_rc.xml @@ -0,0 +1,2 @@ + + diff --git a/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml b/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml index e69de29bb2..ab07cfb2b8 100644 --- a/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml +++ b/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_fw.xml @@ -0,0 +1,2 @@ + + diff --git a/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml b/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml index e69de29bb2..ab07cfb2b8 100644 --- a/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml +++ b/conf/airframes/TestHardware/LisaM_1.0_aspirin_v1.5_rc.xml @@ -0,0 +1,2 @@ + + diff --git a/conf/airframes/TestHardware/Tiny_2.11_fw.xml b/conf/airframes/TestHardware/Tiny_2.11_fw.xml index e69de29bb2..ab07cfb2b8 100644 --- a/conf/airframes/TestHardware/Tiny_2.11_fw.xml +++ b/conf/airframes/TestHardware/Tiny_2.11_fw.xml @@ -0,0 +1,2 @@ + + From 6d140c82c8947107d7a737787d4c7d0b228393ec Mon Sep 17 00:00:00 2001 From: Piotr Esden-Tempski Date: Sat, 11 Feb 2012 23:37:07 -0800 Subject: [PATCH 081/112] Changed some informational warnings to pragma message. --- sw/airborne/arch/stm32/mcu_arch.c | 4 ++-- .../arch/stm32/subsystems/radio_control/spektrum_arch.c | 4 ++-- sw/airborne/modules/ins/ins_xsens.c | 4 ++-- sw/airborne/modules/sensors/imu_ppzuav.c | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/sw/airborne/arch/stm32/mcu_arch.c b/sw/airborne/arch/stm32/mcu_arch.c index 22ea358a60..326a2b20df 100644 --- a/sw/airborne/arch/stm32/mcu_arch.c +++ b/sw/airborne/arch/stm32/mcu_arch.c @@ -47,7 +47,7 @@ void mcu_arch_init(void) { return; #endif #ifdef HSE_TYPE_EXT_CLK -#warning Info: Using external clock +#pragma message "Using external clock." /* Setup the microcontroller system. * Initialize the Embedded Flash Interface, * initialize the PLL and update the SystemFrequency variable. @@ -85,7 +85,7 @@ void mcu_arch_init(void) { while(RCC_GetSYSCLKSource() != 0x08) {} } #else /* HSE_TYPE_EXT_CLK */ -#warning Using normal system clock setup +#pragma message "Using normal system clock setup." SystemInit(); #endif /* HSE_TYPE_EXT_CLK */ /* Set the Vector Table base location at 0x08000000 */ diff --git a/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c b/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c index e56c2e7a3d..f366f8c6f3 100644 --- a/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c +++ b/sw/airborne/arch/stm32/subsystems/radio_control/spektrum_arch.c @@ -87,10 +87,10 @@ typedef struct SpektrumStateStruct SpektrumStateType; SpektrumStateType PrimarySpektrumState = {1,0,0,0,0,0,0,0,0}; #ifdef RADIO_CONTROL_SPEKTRUM_SECONDARY_PORT -#warning "Using secondary spektrum receiver." +#pragma message "Using secondary spektrum receiver." SpektrumStateType SecondarySpektrumState = {1,0,0,0,0,0,0,0,0}; #else -#warning "NOT using secondary spektrum receiver." +#pragma message "NOT using secondary spektrum receiver." #endif int16_t SpektrumBuf[SPEKTRUM_CHANNELS_PER_FRAME*MAX_SPEKTRUM_FRAMES]; diff --git a/sw/airborne/modules/ins/ins_xsens.c b/sw/airborne/modules/ins/ins_xsens.c index f16d597a69..cce76a36ac 100644 --- a/sw/airborne/modules/ins/ins_xsens.c +++ b/sw/airborne/modules/ins/ins_xsens.c @@ -251,14 +251,14 @@ void ins_periodic_task( void ) { case 13: #ifdef AHRS_H_X - #warning Sending XSens Magnetic Declination + #pragma message "Sending XSens Magnetic Declination." xsens_declination = atan2(AHRS_H_Y, AHRS_H_X); XSENS_SetMagneticDeclination(xsens_declination); #endif break; case 12: #ifdef GPS_IMU_LEVER_ARM_X - #warning Sending XSens GPS Arm + #pragma message "Sending XSens GPS Arm." XSENS_SetLeverArmGps(GPS_IMU_LEVER_ARM_X,GPS_IMU_LEVER_ARM_Y,GPS_IMU_LEVER_ARM_Z); #endif break; diff --git a/sw/airborne/modules/sensors/imu_ppzuav.c b/sw/airborne/modules/sensors/imu_ppzuav.c index ba8b137cc8..71e84757e9 100644 --- a/sw/airborne/modules/sensors/imu_ppzuav.c +++ b/sw/airborne/modules/sensors/imu_ppzuav.c @@ -73,10 +73,10 @@ void imu_impl_init(void) #if PERIODIC_FREQUENCY == 60 /* set gyro range to 2000deg/s and low pass at 20Hz (< 60Hz/2) internal sampling at 1kHz */ ppzuavimu_itg3200.buf[1] = (0x03<<3) | (0x04<<0); -# warning Info: ITG3200 read at 50Hz +# pragma message "ITG3200 read at 50Hz." #else # if PERIODIC_FREQUENCY == 120 -# warning Info: ITG3200 read at 100Hz +# pragma message "ITG3200 read at 100Hz." /* set gyro range to 2000deg/s and low pass at 42Hz (< 120Hz/2) internal sampling at 1kHz */ ppzuavimu_itg3200.buf[1] = (0x03<<3) | (0x03<<0); # else From 7f72fcd2cd332aa2b5e943eb69a50da7a4daa1b4 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Sun, 12 Feb 2012 15:53:59 +0100 Subject: [PATCH 082/112] paparazzicenter: green background color for info messages (e.g. via #pragma message) --- sw/supervision/paparazzicenter.ml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/sw/supervision/paparazzicenter.ml b/sw/supervision/paparazzicenter.ml index 6a174620ae..72ca0860a7 100644 --- a/sw/supervision/paparazzicenter.ml +++ b/sw/supervision/paparazzicenter.ml @@ -199,14 +199,15 @@ let () = let tag = GText.tag ~name:color () in tag#set_property (`BACKGROUND color); (color, tag)) - ["red"; "green";"orange"] in + ["red"; "green"; "orange"] in let tag_table = GText.tag_table () in List.iter (fun (_color, tag) -> tag_table#add tag#as_tag) background_tags; let buffer = GText.buffer ~tag_table () in gui#console#set_buffer buffer; let errors = "red", ["error"; "no such file"; "undefined reference"; "failure"] - and warnings = "orange", ["warning"] in + and warnings = "orange", ["warning"] + and info = "green", ["message"; "info"] in let color_regexps = List.map (fun (color, strings) -> @@ -214,7 +215,7 @@ let () = let s = String.concat "\\|" s in let s = ".*\\("^s^"\\)" in color, Str.regexp_case_fold s) - [errors; warnings] in + [errors; warnings; info] in let compute_tags = fun s -> let rec loop = function (color, regexp)::rs -> From 503f4eb57b4c0ea6e2485fc0f896c123dd6582f8 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 13 Feb 2012 17:52:19 +0100 Subject: [PATCH 083/112] paparazzicenter: don't colorize strings with info in green, only on message --- sw/supervision/paparazzicenter.ml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/supervision/paparazzicenter.ml b/sw/supervision/paparazzicenter.ml index 72ca0860a7..c3f9c47d93 100644 --- a/sw/supervision/paparazzicenter.ml +++ b/sw/supervision/paparazzicenter.ml @@ -207,7 +207,7 @@ let () = let errors = "red", ["error"; "no such file"; "undefined reference"; "failure"] and warnings = "orange", ["warning"] - and info = "green", ["message"; "info"] in + and info = "green", ["message"] in let color_regexps = List.map (fun (color, strings) -> From da71b6acb8bb008e0e70191186074b2dddd9cf1f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 13 Feb 2012 19:23:25 +0100 Subject: [PATCH 084/112] manual: switch statements --- doc/manual/style.dox | 24 ++++++++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/doc/manual/style.dox b/doc/manual/style.dox index c0981cfb7f..a3aa6167ba 100644 --- a/doc/manual/style.dox +++ b/doc/manual/style.dox @@ -66,6 +66,30 @@ int32_t f(int32_t x1, int32_t x2) } @endcode +@section styleswitch Switch statements + +- specify a default case +- prefer an enum over defines for the different states +@code +enum state +{ + STATE_FOO = 1, + STATE_BAR = 2 +}; + +switch( state ) +{ + case STATE_FOO: + foo(); + break; + case STATE_BAR: + bar(); + break; + default: + break; +} +@endcode + @section stylecpp Preprocessor directives - For conditional compilation use @c #if instead of @c #ifdef. Someone might write code like: From 763c45a8fe22c9381f0135bbe74dfdb7133d7d7f Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Mon, 13 Feb 2012 20:42:24 +0100 Subject: [PATCH 085/112] paparazzicenter: only colorize green on "pragma message" string --- sw/supervision/paparazzicenter.ml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/supervision/paparazzicenter.ml b/sw/supervision/paparazzicenter.ml index c3f9c47d93..308adcf55c 100644 --- a/sw/supervision/paparazzicenter.ml +++ b/sw/supervision/paparazzicenter.ml @@ -207,7 +207,7 @@ let () = let errors = "red", ["error"; "no such file"; "undefined reference"; "failure"] and warnings = "orange", ["warning"] - and info = "green", ["message"] in + and info = "green", ["pragma message"] in let color_regexps = List.map (fun (color, strings) -> From 0c2b9bdb05dce951a11c5743d3275d5b20365ddf Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Tue, 14 Feb 2012 12:09:48 +0100 Subject: [PATCH 086/112] imu_b2: fix include directive --- sw/airborne/subsystems/imu/imu_b2.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/subsystems/imu/imu_b2.h b/sw/airborne/subsystems/imu/imu_b2.h index 1860501be9..02b7e69c59 100644 --- a/sw/airborne/subsystems/imu/imu_b2.h +++ b/sw/airborne/subsystems/imu/imu_b2.h @@ -169,7 +169,7 @@ } \ } #elif defined IMU_B2_MAG_TYPE && IMU_B2_MAG_TYPE == IMU_B2_MAG_HMC5843 -include "peripherals/hmc5843.h" +#include "peripherals/hmc5843.h" #define foo_handler() {} #define ImuMagEvent(_mag_handler) { \ MagEvent(foo_handler); \ From 0de495c4a03b122f110bae2cae6649e357821afd Mon Sep 17 00:00:00 2001 From: Andre Devitt Date: Mon, 20 Feb 2012 16:57:25 -0500 Subject: [PATCH 087/112] abort an attempted i2c hard reset if attempted toggling of SDA, SCL does not free up lines. --- sw/airborne/arch/stm32/mcu_periph/i2c_arch.c | 24 ++++++++++++++++---- 1 file changed, 20 insertions(+), 4 deletions(-) diff --git a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c index 8d69b3f9da..125b7350c8 100644 --- a/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c +++ b/sw/airborne/arch/stm32/mcu_periph/i2c_arch.c @@ -13,6 +13,10 @@ static inline void i2c_reset_init(struct i2c_periph *p); #define I2C_BUSY 0x20 +// If a hard reset cannot free up SDA, SCL lines abort. Previously stm32 would hang +// when lines stuck i.e. no pullups on I2C lines +#define I2C_MAX_RESET_FAIL_COUNT 20 + #ifdef DEBUG_I2C #define SPURIOUS_INTERRUPT(_periph, _status, _event) { while(1); } #define OUT_OF_SYNC_STATE_MACHINE(_periph, _status, _event) { while(1); } @@ -355,6 +359,7 @@ static inline void i2c_error(struct i2c_periph *p) static inline void i2c_hard_reset(struct i2c_periph *p) { + uint8_t timeout_fails=0; I2C_TypeDef *regs = (I2C_TypeDef *) p->reg_addr; I2C_DeInit(p->reg_addr); @@ -366,10 +371,13 @@ static inline void i2c_hard_reset(struct i2c_periph *p) GPIO_SetBits(GPIOB, p->scl_pin | p->sda_pin); GPIO_Init(GPIOB, &GPIO_InitStructure); - while(GPIO_ReadInputDataBit(GPIOB, p->sda_pin) == Bit_RESET) { + while((GPIO_ReadInputDataBit(GPIOB, p->sda_pin) == Bit_RESET) && timeout_fails < I2C_MAX_RESET_FAIL_COUNT) { // Raise SCL, wait until SCL is high (in case of clock stretching) GPIO_SetBits(GPIOB, p->scl_pin); - while (GPIO_ReadInputDataBit(GPIOB, p->scl_pin) == Bit_RESET); + while ((GPIO_ReadInputDataBit(GPIOB, p->scl_pin) == Bit_RESET) && timeout_fails < I2C_MAX_RESET_FAIL_COUNT) { + i2c_delay(); + timeout_fails++; + } i2c_delay(); // Lower SCL, wait @@ -379,6 +387,7 @@ static inline void i2c_hard_reset(struct i2c_periph *p) // Raise SCL, wait GPIO_SetBits(GPIOB, p->scl_pin); i2c_delay(); + timeout_fails++; } // Generate a start condition followed by a stop condition @@ -391,10 +400,17 @@ static inline void i2c_hard_reset(struct i2c_periph *p) // Raise both SCL and SDA and wait for SCL high (in case of clock stretching) GPIO_SetBits(GPIOB, p->scl_pin | p->sda_pin); - while (GPIO_ReadInputDataBit(GPIOB, p->scl_pin) == Bit_RESET); + while (GPIO_ReadInputDataBit(GPIOB, p->scl_pin) == Bit_RESET && timeout_fails < I2C_MAX_RESET_FAIL_COUNT) { + i2c_delay(); + timeout_fails++; + } // Wait for SDA to be high - while (GPIO_ReadInputDataBit(GPIOB, p->sda_pin) != Bit_SET); + while (GPIO_ReadInputDataBit(GPIOB, p->sda_pin) != Bit_SET && timeout_fails < I2C_MAX_RESET_FAIL_COUNT) + { + i2c_delay(); + timeout_fails++; + } // SCL and SDA should be high at this point, bus should be free // Return the GPIO pins to the alternate function From e4985f362a803aef779c87ab6fbdafd9f60db46d Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 23 Feb 2012 15:42:23 +0100 Subject: [PATCH 088/112] changes on navgo board for new baro and update some airframes --- conf/airframes/ENAC/fixed-wing/twinjet2.xml | 105 +----------------- conf/airframes/ENAC/quadrotor/blender.xml | 42 +++---- conf/airframes/ENAC/quadrotor/navgo.xml | 48 ++++---- conf/autopilot/rotorcraft.makefile | 8 +- .../subsystems/shared/imu_navgo.makefile | 2 + sw/airborne/arch/lpc21/mcu_periph/spi_arch.c | 2 + sw/airborne/boards/navgo/baro_board.c | 48 ++++---- sw/airborne/boards/navgo/baro_board.h | 16 +-- sw/airborne/boards/navgo/imu_navgo.c | 4 +- sw/airborne/boards/navgo_1.0.h | 23 ++-- sw/airborne/peripherals/mcp355x.c | 16 +-- 11 files changed, 101 insertions(+), 213 deletions(-) diff --git a/conf/airframes/ENAC/fixed-wing/twinjet2.xml b/conf/airframes/ENAC/fixed-wing/twinjet2.xml index 959a400c62..a2c9fe7535 100644 --- a/conf/airframes/ENAC/fixed-wing/twinjet2.xml +++ b/conf/airframes/ENAC/fixed-wing/twinjet2.xml @@ -14,10 +14,10 @@ - + @@ -33,7 +33,7 @@ - + @@ -217,103 +217,4 @@
- - diff --git a/conf/airframes/ENAC/quadrotor/blender.xml b/conf/airframes/ENAC/quadrotor/blender.xml index c1682f0477..7be545c03f 100644 --- a/conf/airframes/ENAC/quadrotor/blender.xml +++ b/conf/airframes/ENAC/quadrotor/blender.xml @@ -1,11 +1,11 @@ - + @@ -22,13 +22,13 @@ - - - + + + @@ -48,17 +48,11 @@ - - - - - - + @@ -67,20 +61,15 @@ - + +
- - - -
- - +
diff --git a/conf/airframes/ENAC/quadrotor/navgo.xml b/conf/airframes/ENAC/quadrotor/navgo.xml index a42bd6d411..cbd3ae1fc3 100644 --- a/conf/airframes/ENAC/quadrotor/navgo.xml +++ b/conf/airframes/ENAC/quadrotor/navgo.xml @@ -21,7 +21,6 @@ - @@ -30,11 +29,11 @@ - - - - + + + + @@ -73,31 +72,39 @@
- - - + + + - - - + + + - - - + + + - - - + + + + + + + + + @@ -125,6 +132,8 @@ + + @@ -149,7 +158,8 @@
- + +
diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile index c8e4b37502..a4d248a8be 100644 --- a/conf/autopilot/rotorcraft.makefile +++ b/conf/autopilot/rotorcraft.makefile @@ -145,9 +145,11 @@ else ifeq ($(BOARD), lisa_l) ap.CFLAGS += -DUSE_I2C2 else ifeq ($(BOARD), navgo) ap.CFLAGS += -DROTORCRAFT_BARO_LED=$(BARO_LED) -ap.CFLAGS += -DUSE_I2C1 -ap.CFLAGS += -DADS1114_I2C_DEVICE=i2c1 -ap.srcs += peripherals/ads1114.c +include $(CFG_ROTORCRAFT)/spi.makefile +ap.CFLAGS += -DUSE_SPI_SLAVE0 +ap.CFLAGS += -DSPI_NO_UNSELECT_SLAVE +ap.CFLAGS += -DSPI_MASTER +ap.srcs += peripherals/mcp355x.c endif # diff --git a/conf/autopilot/subsystems/shared/imu_navgo.makefile b/conf/autopilot/subsystems/shared/imu_navgo.makefile index e10385bbc3..2a24fbf0d0 100644 --- a/conf/autopilot/subsystems/shared/imu_navgo.makefile +++ b/conf/autopilot/subsystems/shared/imu_navgo.makefile @@ -12,10 +12,12 @@ IMU_NAVGO_CFLAGS += -DUSE_I2C1 -DI2C1_SCLL=25 -DI2C1_SCLH=25 IMU_NAVGO_CFLAGS += -DITG3200_I2C_DEVICE=$(IMU_NAVGO_I2C_DEVICE) IMU_NAVGO_CFLAGS += -DITG3200_I2C_ADDR=ITG3200_ADDR_ALT IMU_NAVGO_CFLAGS += -DITG3200_SMPLRT_DIV=1 +IMU_NAVGO_CFLAGS += -DITG3200_DLFP_CFG=5 IMU_NAVGO_SRCS += peripherals/itg3200.c IMU_NAVGO_CFLAGS += -DADXL345_I2C_DEVICE=$(IMU_NAVGO_I2C_DEVICE) IMU_NAVGO_CFLAGS += -DADXL345_I2C_ADDR=ADXL345_ADDR_ALT +IMU_NAVGO_CFLAGS += -DADXL345_BW_RATE=0x8 IMU_NAVGO_SRCS += peripherals/adxl345.i2c.c IMU_NAVGO_CFLAGS += -DHMC58XX_I2C_DEVICE=$(IMU_NAVGO_I2C_DEVICE) diff --git a/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c index 5ec122bcb8..d7286e6dcd 100644 --- a/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c +++ b/sw/airborne/arch/lpc21/mcu_periph/spi_arch.c @@ -193,7 +193,9 @@ void SPI1_ISR(void) { } if (bit_is_set(SSPMIS, RTMIS)) { /* Rx fifo is not empty and no receive took place in the last 32 bits period */ +#if !SPI_NO_UNSELECT_SLAVE SpiUnselectCurrentSlave(); +#endif SpiReceive(); SpiDisableRti(); SpiClearRti(); /* clear interrupt */ diff --git a/sw/airborne/boards/navgo/baro_board.c b/sw/airborne/boards/navgo/baro_board.c index 87ac9fdbe7..20048139ab 100644 --- a/sw/airborne/boards/navgo/baro_board.c +++ b/sw/airborne/boards/navgo/baro_board.c @@ -31,53 +31,51 @@ /* Common Baro struct */ struct Baro baro; -/* Number of values to compute an offset at startup */ -#define OFFSET_NBSAMPLES_AVRG 300 -uint16_t offset_cnt; - -#ifdef USE_BARO_AS_ALTIMETER -/* Weight for offset IIR filter */ -#define OFFSET_FILTER 7 - -float baro_alt; -float baro_alt_offset; -#endif +/* Counter to init mcp355x at startup */ +#define STARTUP_COUNTER 200 +uint16_t startup_cnt; void baro_init( void ) { - ads1114_init(); + mcp355x_init(); baro.status = BS_UNINITIALIZED; baro.absolute = 0; baro.differential = 0; /* not handled on this board */ #ifdef ROTORCRAFT_BARO_LED LED_OFF(ROTORCRAFT_BARO_LED); #endif - offset_cnt = OFFSET_NBSAMPLES_AVRG; -#ifdef USE_BARO_AS_ALTIMETER - baro_alt = 0.; - baro_alt_offset = 0.; -#endif + startup_cnt = STARTUP_COUNTER; } +// Need to play with slave select +#include "mcu_periph/spi.h" + void baro_periodic( void ) { if (baro.status == BS_UNINITIALIZED) { -#ifdef USE_BARO_AS_ALTIMETER - // IIR filter to compute an initial offset - baro_alt_offset = (OFFSET_FILTER * baro_alt_offset + (float)baro.absolute) / (OFFSET_FILTER + 1); -#endif + /** + * Crappy code to empty the buffer + * then unselect the device (goes to shutdown ?) + * reselect to go to continious conversion mode + * make some readings before setting BS_RUNNING + * don't unselect the slave ! + */ + if (startup_cnt == 150) { SpiSelectSlave0(); mcp355x_read(); } + else if (startup_cnt == 149) { SpiUnselectSlave0(); } + else if (startup_cnt == 100) { SpiSelectSlave0(); } + else if (startup_cnt < 90) { RunOnceEvery(4, mcp355x_read()); } // decrease init counter - --offset_cnt; + --startup_cnt; #ifdef ROTORCRAFT_BARO_LED LED_TOGGLE(ROTORCRAFT_BARO_LED); #endif - if (offset_cnt == 0) { + if (startup_cnt == 0) { baro.status = BS_RUNNING; #ifdef ROTORCRAFT_BARO_LED LED_ON(ROTORCRAFT_BARO_LED); #endif } } - // Read the ADC - ads1114_read(); + // Read the ADC (at 50/4 Hz, conversion time is 68 ms) + else { RunOnceEvery(4,mcp355x_read()); } } diff --git a/sw/airborne/boards/navgo/baro_board.h b/sw/airborne/boards/navgo/baro_board.h index de705d46d0..250476b148 100644 --- a/sw/airborne/boards/navgo/baro_board.h +++ b/sw/airborne/boards/navgo/baro_board.h @@ -31,22 +31,16 @@ #include "std.h" -#include "peripherals/ads1114.h" - -#ifdef USE_BARO_AS_ALTIMETER -extern float baro_alt; -extern float baro_alt_offset; -#define BaroAltHandler() { baro_alt = BARO_SENS*(baro_alt_offset - (float)baro.absolute); } -#endif +#include "peripherals/mcp355x.h" #define BARO_FILTER_GAIN 5 #define BaroEvent(_b_abs_handler, _b_diff_handler) { \ - Ads1114Event(); \ - if (ads1114_data_available) { \ - baro.absolute = (baro.absolute + BARO_FILTER_GAIN*Ads1114GetValue()) / (BARO_FILTER_GAIN+1); \ + mcp355x_event(); \ + if (mcp355x_data_available) { \ + baro.absolute = (baro.absolute + BARO_FILTER_GAIN*mcp355x_data) / (BARO_FILTER_GAIN+1); \ _b_abs_handler(); \ - ads1114_data_available = FALSE; \ + mcp355x_data_available = FALSE; \ } \ } diff --git a/sw/airborne/boards/navgo/imu_navgo.c b/sw/airborne/boards/navgo/imu_navgo.c index b872219e9e..cf19cfefd6 100644 --- a/sw/airborne/boards/navgo/imu_navgo.c +++ b/sw/airborne/boards/navgo/imu_navgo.c @@ -103,7 +103,7 @@ void imu_navgo_event( void ) // If the itg3200 I2C transaction has succeeded: convert the data itg3200_event(); if (itg3200_data_available) { - RATES_COPY(imu.gyro_unscaled, itg3200_data); + RATES_ASSIGN(imu.gyro_unscaled, -itg3200_data.q, itg3200_data.p, itg3200_data.r); itg3200_data_available = FALSE; gyr_valid = TRUE; } @@ -119,7 +119,7 @@ void imu_navgo_event( void ) // HMC58XX event task hmc58xx_event(); if (hmc58xx_data_available) { - VECT3_ASSIGN(imu.mag_unscaled, -hmc58xx_data.x, -hmc58xx_data.y, hmc58xx_data.z); + VECT3_ASSIGN(imu.mag_unscaled, hmc58xx_data.x, hmc58xx_data.y, hmc58xx_data.z); hmc58xx_data_available = FALSE; mag_valid = TRUE; } diff --git a/sw/airborne/boards/navgo_1.0.h b/sw/airborne/boards/navgo_1.0.h index 17a6fbf118..3f1121dbbe 100644 --- a/sw/airborne/boards/navgo_1.0.h +++ b/sw/airborne/boards/navgo_1.0.h @@ -18,17 +18,17 @@ #define PCLK (CCLK / PBSD_VAL) /* Onboard LEDs */ -#define LED_1_BANK 1 -#define LED_1_PIN 25 +#define LED_1_BANK 0 +#define LED_1_PIN 22 #define LED_2_BANK 1 -#define LED_2_PIN 24 +#define LED_2_PIN 28 #define LED_3_BANK 1 -#define LED_3_PIN 23 +#define LED_3_PIN 29 #define LED_4_BANK 1 -#define LED_4_PIN 31 +#define LED_4_PIN 30 /* PPM : rc rx on P0.28 ( CAP0.2 ) */ #define PPM_PINSEL PINSEL1 @@ -45,19 +45,22 @@ /* battery */ /* allow to define ADC_CHANNEL_VSUPPLY in the airframe file*/ #ifndef ADC_CHANNEL_VSUPPLY -#define ADC_CHANNEL_VSUPPLY AdcBank1(3) -#ifndef USE_AD1 -#define USE_AD1 +#define ADC_CHANNEL_VSUPPLY AdcBank0(2) +#ifndef USE_AD0 +#define USE_AD0 #endif -#define USE_AD1_3 +#define USE_AD0_2 #endif -#define DefaultVoltageOfAdc(adc) (0.01837*adc) +#define DefaultVoltageOfAdc(adc) (0.017889*adc) /* SPI (SSP) */ #define SPI_SELECT_SLAVE0_PORT 0 #define SPI_SELECT_SLAVE0_PIN 20 +//#define SPI_SELECT_SLAVE1_PORT 1 +//#define SPI_SELECT_SLAVE1_PIN 19 + #define SPI1_DRDY_PINSEL PINSEL1 #define SPI1_DRDY_PINSEL_BIT 0 #define SPI1_DRDY_PINSEL_VAL 1 diff --git a/sw/airborne/peripherals/mcp355x.c b/sw/airborne/peripherals/mcp355x.c index 386f1aae59..3eec8438ab 100644 --- a/sw/airborne/peripherals/mcp355x.c +++ b/sw/airborne/peripherals/mcp355x.c @@ -41,32 +41,20 @@ void mcp355x_init(void) { void mcp355x_read(void) { spi_buffer_length = 4; spi_buffer_input = mcp355x_spi_buf; - SpiSelectSlave0(); + //SpiSelectSlave0(); SpiStart(); } -#ifndef DOWNLINK_DEVICE -#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE -#endif - -#include "mcu_periph/uart.h" -#include "messages.h" -#include "downlink.h" - void mcp355x_event(void) { - static uint32_t filtered = 0; if (spi_message_received) { spi_message_received = FALSE; if ((mcp355x_spi_buf[0]>>4) == 0) { - //mcp355x_data = (int32_t)(((uint32_t)mcp355x_spi_buf[0]<<16) | ((uint32_t)mcp355x_spi_buf[1]<<8) | (mcp355x_spi_buf[2])); mcp355x_data = (int32_t)( ((uint32_t)mcp355x_spi_buf[0]<<17) | ((uint32_t)mcp355x_spi_buf[1]<<9) | ((uint32_t)mcp355x_spi_buf[2]<<1) | (mcp355x_spi_buf[3]>>7)); - filtered = (5*filtered + mcp355x_data) / (6); - DOWNLINK_SEND_DEBUG(DefaultChannel,4,mcp355x_spi_buf); - DOWNLINK_SEND_BARO_RAW(DefaultChannel,&mcp355x_data,&filtered); + mcp355x_data_available = TRUE; } } } From ecbb88ac3ac607a68d6885e70d5dc7bfa5032e28 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 23 Feb 2012 17:56:17 +0100 Subject: [PATCH 089/112] hide the cam target point at gcs startup --- sw/lib/ocaml/mapTrack.ml | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/sw/lib/ocaml/mapTrack.ml b/sw/lib/ocaml/mapTrack.ml index 2bdbc979c0..a38356e88c 100644 --- a/sw/lib/ocaml/mapTrack.ml +++ b/sw/lib/ocaml/mapTrack.ml @@ -75,13 +75,15 @@ class track = fun ?(name="Noname") ?(size = 500) ?(color="red") (geomap:MapCanva (** rectangle representing the field covered by the cam *) let _ac_cam_targeted = ignore ( GnoCanvas.ellipse ~x1: (-. 2.5) ~y1: (-. 2.5 ) ~x2: 2.5 ~y2: 2.5 ~fill_color:color ~props:[`WIDTH_UNITS 1.; `OUTLINE_COLOR color; `FILL_STIPPLE (Gdk.Bitmap.create_from_data ~width:2 ~height:2 "\002\001")] cam) in + let _ = cam#hide () in let mission_target = GnoCanvas.group group in (** red circle : target of the mission *) - let ac_mission_target = - GnoCanvas.ellipse ~x1: (-5.) ~y1: (-5.) ~x2: 5. ~y2: 5. ~fill_color:"red" ~props:[`WIDTH_UNITS 1.; `OUTLINE_COLOR "red"; `FILL_STIPPLE (Gdk.Bitmap.create_from_data ~width:2 ~height:2 "\002\001")] mission_target in - let _ = ac_mission_target#hide () in + let _ac_mission_target = + ignore ( GnoCanvas.ellipse ~x1: (-5.) ~y1: (-5.) ~x2: 5. ~y2: 5. ~fill_color:"red" ~props:[`WIDTH_UNITS 1.; `OUTLINE_COLOR "red"; `FILL_STIPPLE (Gdk.Bitmap.create_from_data ~width:2 ~height:2 "\002\001")] mission_target) in + (*let _ = ac_mission_target#hide () in*) + let _ = mission_target#hide () in (** data at map scale *) let max_cam_half_height_scaled = 10000.0 in @@ -92,6 +94,8 @@ class track = fun ?(name="Noname") ?(size = 500) ?(color="red") (geomap:MapCanva let _desired_circle = GnoCanvas.ellipse group and _desired_segment = GnoCanvas.line group in + let _ = aircraft#raise_to_top () in + object (self) val mutable top = 0 val mutable color = color From 7b8b90442aa31191401e37d57dce159ea5c7f6b6 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 23 Feb 2012 18:01:04 +0100 Subject: [PATCH 090/112] forgot to save the latest change... --- sw/lib/ocaml/mapTrack.ml | 1 - 1 file changed, 1 deletion(-) diff --git a/sw/lib/ocaml/mapTrack.ml b/sw/lib/ocaml/mapTrack.ml index a38356e88c..42501fad1f 100644 --- a/sw/lib/ocaml/mapTrack.ml +++ b/sw/lib/ocaml/mapTrack.ml @@ -82,7 +82,6 @@ class track = fun ?(name="Noname") ?(size = 500) ?(color="red") (geomap:MapCanva (** red circle : target of the mission *) let _ac_mission_target = ignore ( GnoCanvas.ellipse ~x1: (-5.) ~y1: (-5.) ~x2: 5. ~y2: 5. ~fill_color:"red" ~props:[`WIDTH_UNITS 1.; `OUTLINE_COLOR "red"; `FILL_STIPPLE (Gdk.Bitmap.create_from_data ~width:2 ~height:2 "\002\001")] mission_target) in - (*let _ = ac_mission_target#hide () in*) let _ = mission_target#hide () in (** data at map scale *) From 95e6f124f09d663a9e334a1faf093e3790718cf6 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Fri, 24 Feb 2012 14:43:23 +0100 Subject: [PATCH 091/112] remove crappy code, hw is fixed :) --- sw/airborne/boards/navgo/baro_board.c | 20 ++++---------------- 1 file changed, 4 insertions(+), 16 deletions(-) diff --git a/sw/airborne/boards/navgo/baro_board.c b/sw/airborne/boards/navgo/baro_board.c index 20048139ab..b42b69ee3a 100644 --- a/sw/airborne/boards/navgo/baro_board.c +++ b/sw/airborne/boards/navgo/baro_board.c @@ -27,6 +27,7 @@ #include "subsystems/sensors/baro.h" #include "led.h" +#include "mcu_periph/spi.h" /* Common Baro struct */ struct Baro baro; @@ -37,6 +38,7 @@ uint16_t startup_cnt; void baro_init( void ) { mcp355x_init(); + SpiSelectSlave0(); // never unselect this slave (continious conversion mode) baro.status = BS_UNINITIALIZED; baro.absolute = 0; baro.differential = 0; /* not handled on this board */ @@ -46,24 +48,10 @@ void baro_init( void ) { startup_cnt = STARTUP_COUNTER; } -// Need to play with slave select -#include "mcu_periph/spi.h" - void baro_periodic( void ) { if (baro.status == BS_UNINITIALIZED) { - /** - * Crappy code to empty the buffer - * then unselect the device (goes to shutdown ?) - * reselect to go to continious conversion mode - * make some readings before setting BS_RUNNING - * don't unselect the slave ! - */ - if (startup_cnt == 150) { SpiSelectSlave0(); mcp355x_read(); } - else if (startup_cnt == 149) { SpiUnselectSlave0(); } - else if (startup_cnt == 100) { SpiSelectSlave0(); } - else if (startup_cnt < 90) { RunOnceEvery(4, mcp355x_read()); } - // decrease init counter + // Run some loops to get correct readings from the adc --startup_cnt; #ifdef ROTORCRAFT_BARO_LED LED_TOGGLE(ROTORCRAFT_BARO_LED); @@ -76,6 +64,6 @@ void baro_periodic( void ) { } } // Read the ADC (at 50/4 Hz, conversion time is 68 ms) - else { RunOnceEvery(4,mcp355x_read()); } + RunOnceEvery(4,mcp355x_read()); } From 4c80505efd818d02feac7ff919767af81d0fedff Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 24 Feb 2012 15:56:24 +0100 Subject: [PATCH 092/112] replaced README with markdown formatted version --- README | 100 ------------------------------------------------------ README.md | 76 +++++++++++++++++++++++++++++++++++++++++ 2 files changed, 76 insertions(+), 100 deletions(-) delete mode 100644 README create mode 100644 README.md diff --git a/README b/README deleted file mode 100644 index ed5b36cc2c..0000000000 --- a/README +++ /dev/null @@ -1,100 +0,0 @@ -# Paparazzi $Id$ -# Copyright (C) 2003-2010 The Paparazzi Team -# -# This file is part of Paparazzi. -# -# Paparazzi is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 2, or (at your option) -# any later version. -# -# Paparazzi is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of -# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -# GNU General Public License for more details. -# -# You should have received a copy of the GNU General Public License -# along with Paparazzi; see the file COPYING. If not, write to -# the Free Software Foundation, 59 Temple Place - Suite 330, -# Boston, MA 02111-1307, USA. - - -Intro ------ - -Paparazzi is an attempt to develop a free software Unmanned (Air) Vehicle System. - As of today the system is being used successfuly by a number of hobyists, universities and companies all over the world, on vehicle of various size ( 100g to 25Kg ) and of various nature ( fixed wing, rotorcrafts, boats and surface vehicles). - -Up to date informations are available from the wiki website - - http://paparazzi.enac.fr - -and from the mailing list (http://savannah.nongnu.org/mail/?group=paparazzi) -and the IRC channel (freenode, #paparazzi). - -Directories quick and dirty description: ---------------------------------------- - -conf: the configuration directory (airframe, radio, ... descriptions). - -data: where to put read-only data (e.g. maps, terrain elevation files, icons) - -sw: software (onboard, ground station, simulation, ...) - -var: products of compilation, cache for the map tiles, ... - -debian: Debian packaging control files - - -Required Software ------------------ - -Installation is described in the wiki (paparazzi.enac.fr/wiki/Installation). -Main requirements include - - OCaml (ocaml.org), xml-light library (http://tech.motion-twin.com/xmllight) - - gcc, GTK2, Glib2, libgnomecanvas, libxml2 - - ARM7 micro-controller development environnment (gcc, loader, libc, binutils) - - ... - -For Debian or Ubuntu users, required packages are available at - - http://paparazzi.enac.fr/debian - - - - "paparazzi-dev" will provide everything needed to compile and run the ground segment and the simulator. If something is missing, please report it. - - "paparazzi-arm7" is required to compile the code for LPC21 based boards ( tiny, twog, booz, etc). - - "paparazzi-stm32" is needed for building code for STM32 based boards (lisa/L, lisa/M) - - "paparazzi-omap" is needed for building code for the optional Gumstix Overo module available on lisa/L - - - "paparazzi-jsbsim" is needed for using jsbsim as flight dynamic model for the simulator. - -Compilation and demo simulation -------------------------------- - - 1) type "make" in the top directory to compile all the libraries and tools. - - 2) "./paparazzi" to run the Paparazzi Center - - 3) Select the "Microjet" aircraft in the upper-left A/C -combo box. Select "sim" from upper-middle "target" combo box. Click -"Build". When the compilation is finished, select "Simulation" from -the upper-right session combo box and click "Execute". - - 4) In the GCS, wait about 10s for the aircraft to be in the "Holding -point" navigation block. Switch to the "Takeoff" block (lower-left -blue airway button in the strip). Takeoff with the green launch button. - -Uploading of the embedded software ----------------------------------- - - 1) Power the flight controller board while it is connected to the PC with -the USB cable. - - 2) From the Paparazzi center, select the "ap" target, and click "Upload". - - -Flight -------------------------------------- - - 1) From the Paparazzi Center, select the flight session and ... do -the same than in simulation ! diff --git a/README.md b/README.md new file mode 100644 index 0000000000..f929ceab5e --- /dev/null +++ b/README.md @@ -0,0 +1,76 @@ +Paparazzi UAS +============= + +Paparazzi is an attempt to develop a free software Unmanned (Air) Vehicle System. + As of today the system is being used successfuly by a number of hobyists, universities and companies all over the world, on vehicle of various size ( 100g to 25Kg ) and of various nature ( fixed wing, rotorcrafts, boats and surface vehicles). + +Up to date informations are available from the wiki website + + http://paparazzi.enac.fr + +and from the mailing list (http://savannah.nongnu.org/mail/?group=paparazzi) +and the IRC channel (freenode, #paparazzi). + + +Required Software +----------------- + +Installation is described in the wiki (http://paparazzi.enac.fr/wiki/Installation). + +For Ubuntu users, required packages are available at + + https://launchpad.net/~paparazzi-uav/+archive/ppa + +For Debian users: + + http://paparazzi.enac.fr/debian + + +- **paparazzi-dev** is the meta-package that depends on everything needed to compile and run the ground segment and the simulator. +- **paparazzi-arm-multilib** ARM cross-compiling toolchain for LPC21 and STM32 based boards. +- **paparazzi-omap** toolchain for the optional Gumstix Overo module available on lisa/L. +- **paparazzi-jsbsim** is needed for using JSBSim as flight dynamic model for the simulator. + + +Directories quick and dirty description: +---------------------------------------- + +conf: the configuration directory (airframe, radio, ... descriptions). + +data: where to put read-only data (e.g. maps, terrain elevation files, icons) + +doc: documentation (diagrams, manual source files, ...) + +sw: software (onboard, ground station, simulation, ...) + +var: products of compilation, cache for the map tiles, ... + + +Compilation and demo simulation +------------------------------- + +1. type "make" in the top directory to compile all the libraries and tools. + +2. "./paparazzi" to run the Paparazzi Center + +3. Select the "Microjet" aircraft in the upper-left A/C combo box. + Select "sim" from upper-middle "target" combo box. Click "Build". + When the compilation is finished, select "Simulation" from + the upper-right session combo box and click "Execute". + +4. In the GCS, wait about 10s for the aircraft to be in the "Holding point" navigation block. + Switch to the "Takeoff" block (lower-left blue airway button in the strip). + Takeoff with the green launch button. + +Uploading of the embedded software +================================== + +1. Power the flight controller board while it is connected to the PC with the USB cable. + +2. From the Paparazzi center, select the "ap" target, and click "Upload". + + +Flight +====== + +1. From the Paparazzi Center, select the flight session and ... do the same than in simulation ! From 3bed7797bc344b0a24d1c3c9bc74ea890e77ac14 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 24 Feb 2012 16:06:37 +0100 Subject: [PATCH 093/112] Update README.md --- README.md | 31 ++++++++++++------------------- 1 file changed, 12 insertions(+), 19 deletions(-) diff --git a/README.md b/README.md index f929ceab5e..8400e0d98a 100644 --- a/README.md +++ b/README.md @@ -4,11 +4,9 @@ Paparazzi UAS Paparazzi is an attempt to develop a free software Unmanned (Air) Vehicle System. As of today the system is being used successfuly by a number of hobyists, universities and companies all over the world, on vehicle of various size ( 100g to 25Kg ) and of various nature ( fixed wing, rotorcrafts, boats and surface vehicles). -Up to date informations are available from the wiki website +Up to date information is available in the wiki http://paparazzi.enac.fr - http://paparazzi.enac.fr - -and from the mailing list (http://savannah.nongnu.org/mail/?group=paparazzi) +and from the mailing list [paparazzi-devel@nongnu.org] (http://savannah.nongnu.org/mail/?group=paparazzi) and the IRC channel (freenode, #paparazzi). @@ -17,13 +15,8 @@ Required Software Installation is described in the wiki (http://paparazzi.enac.fr/wiki/Installation). -For Ubuntu users, required packages are available at - - https://launchpad.net/~paparazzi-uav/+archive/ppa - -For Debian users: - - http://paparazzi.enac.fr/debian +For Ubuntu users, required packages are available in the [paparazzi-uav PPA] (https://launchpad.net/~paparazzi-uav/+archive/ppa), +Debian users can use http://paparazzi.enac.fr/debian - **paparazzi-dev** is the meta-package that depends on everything needed to compile and run the ground segment and the simulator. @@ -35,15 +28,15 @@ For Debian users: Directories quick and dirty description: ---------------------------------------- -conf: the configuration directory (airframe, radio, ... descriptions). +_conf_: the configuration directory (airframe, radio, ... descriptions). -data: where to put read-only data (e.g. maps, terrain elevation files, icons) +_data_: where to put read-only data (e.g. maps, terrain elevation files, icons) -doc: documentation (diagrams, manual source files, ...) +_doc_: documentation (diagrams, manual source files, ...) -sw: software (onboard, ground station, simulation, ...) +_sw_: software (onboard, ground station, simulation, ...) -var: products of compilation, cache for the map tiles, ... +_var_: products of compilation, cache for the map tiles, ... Compilation and demo simulation @@ -63,7 +56,7 @@ Compilation and demo simulation Takeoff with the green launch button. Uploading of the embedded software -================================== +---------------------------------- 1. Power the flight controller board while it is connected to the PC with the USB cable. @@ -71,6 +64,6 @@ Uploading of the embedded software Flight -====== +------ -1. From the Paparazzi Center, select the flight session and ... do the same than in simulation ! +1. From the Paparazzi Center, select the flight session and ... do the same than in simulation ! \ No newline at end of file From 4c5c9f6e1788cc3b34ca8a88416603692df53e04 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Mon, 27 Feb 2012 18:39:17 +0100 Subject: [PATCH 094/112] makefile to produce a shared library based on the pprz math lib --- sw/airborne/math/Makefile | 47 +++++++++++++++++++++++++++++++++ sw/airborne/math/README | 34 ++++++++++++++++++++++++ sw/airborne/math/pprzmath.pc.in | 9 +++++++ 3 files changed, 90 insertions(+) create mode 100644 sw/airborne/math/Makefile create mode 100644 sw/airborne/math/README create mode 100644 sw/airborne/math/pprzmath.pc.in diff --git a/sw/airborne/math/Makefile b/sw/airborne/math/Makefile new file mode 100644 index 0000000000..782cfb0b30 --- /dev/null +++ b/sw/airborne/math/Makefile @@ -0,0 +1,47 @@ +# Build shared pprz math library +# + +CC= gcc +CFLAGS= -fpic +INCLUDES= -I $(PAPARAZZI_SRC)/sw/include -I $(PAPARAZZI_SRC)/sw/airborne + +# build in ../../../var/build/math +ifndef BUILDDIR +BUILDDIR=../../../var/build/math +endif + +ifndef PREFIX +PREFIX=/usr +endif +LIB_INSTALLDIR=${PREFIX}/lib +INCLUDE_INSTALLDIR=${PREFIX}/include/pprz +PKGCONFIG_INSTALLDIR=${PREFIX}/lib/pkgconfig +PKGCONFIG_FILE=pprzmath.pc + +SRC= $(wildcard *.c) +OBJ= $(addprefix $(BUILDDIR)/,$(SRC:.c=.o)) + +LIBNAME=libpprzmath + +all: + @cat README + +shared_lib: $(OBJ) + $(CC) -shared -o $(BUILDDIR)/$(LIBNAME).so $(OBJ) + +install_shared_lib: shared_lib + test -d $(LIB_INSTALLDIR) || mkdir -p $(LIB_INSTALLDIR) + cp $(BUILDDIR)/$(LIBNAME).so $(LIB_INSTALLDIR) + test -d $(INCLUDE_INSTALLDIR)/math || mkdir -p $(INCLUDE_INSTALLDIR)/math + cp *.h $(INCLUDE_INSTALLDIR)/math + cp ../../include/std.h $(INCLUDE_INSTALLDIR) + test -d $(PKGCONFIG_INSTALLDIR) || mkdir -p $(PKGCONFIG_INSTALLDIR) + sed -e 's#PREFIX#$(PREFIX)#g' $(PKGCONFIG_FILE).in > $(PKGCONFIG_INSTALLDIR)/$(PKGCONFIG_FILE) + +$(BUILDDIR)/%.o: %.c + test -d $(BUILDDIR) || mkdir -p $(BUILDDIR) + $(CC) -c $< $(CFLAGS) $(INCLUDES) -o $@ + +clean: + rm -f $(BUILDDIR)/*.o $(BUILDDIR)/$(LIBNAME).so + diff --git a/sw/airborne/math/README b/sw/airborne/math/README new file mode 100644 index 0000000000..9c68398093 --- /dev/null +++ b/sw/airborne/math/README @@ -0,0 +1,34 @@ +Math lib used in all airborne code of paparazzi + +HOWTO install a shared library to use in other projects + +1. Build library: in this folder, type + make shared_lib + + the default build directory is var/build/math + to change it: BUILDDIR= make shared_lib + +2. Install library: in this folder, type + make install_shared_lib + + the default install dir is /usr + and will install files in + /usr/lib + /usr/lib/pkgconfig + /usr/include/pprz + + to change the install dir: PREFIX= make install_shared_lib + + note that the default install dir needs root privilege + +HOWTO use the shared library + +1. with pkg-config --cflags --libs + +2. by hand: + LIBS: -L/lib -lpprzmath + CFLAGS: -I/include/pprz + + +"make clean" will only clean the build directory + diff --git a/sw/airborne/math/pprzmath.pc.in b/sw/airborne/math/pprzmath.pc.in new file mode 100644 index 0000000000..b70fbd26f4 --- /dev/null +++ b/sw/airborne/math/pprzmath.pc.in @@ -0,0 +1,9 @@ +prefix=PREFIX +exec_prefix=${prefix} +libdir=${exec_prefix}/lib +includedir=${exec_prefix}/include +Name: pprzmath +Description: math library used in Paparazzi project (http://paparazzi.enac.fr) +Version:0.1 +Libs: -L${libdir} -lpprzmath +Cflags: -I${includedir}/pprz From 00f6cd6fed94fda1547b4e55f34c55fd93573f85 Mon Sep 17 00:00:00 2001 From: Gautier Hattenberger Date: Thu, 1 Mar 2012 11:06:09 +0100 Subject: [PATCH 095/112] delete curves before closing a window (suppress warning); replace tab by spaces --- sw/logalizer/plotter.ml | 364 +++++++++++++++++++++------------------- 1 file changed, 187 insertions(+), 177 deletions(-) diff --git a/sw/logalizer/plotter.ml b/sw/logalizer/plotter.ml index d925600091..fc1f523d88 100644 --- a/sw/logalizer/plotter.ml +++ b/sw/logalizer/plotter.ml @@ -80,6 +80,7 @@ type status = class plot = fun ~size ~width ~height ~packing () -> let curves = Hashtbl.create 3 in + let bindings = Hashtbl.create 3 in object (self) inherit Gtk_tools.pixmap_in_drawin_area ~width ~height ~packing () as pm @@ -119,184 +120,189 @@ class plot = fun ~size ~width ~height ~packing () -> method reset () = if auto_scale then begin - min <- max_float; - max <- -. max_float + min <- max_float; + max <- -. max_float end; Hashtbl.iter (fun _ a -> - a.index <- 0; - a.average#set_value 0.; - a.stdev#set_value 0.; - for i = 0 to Array.length a.array - 1 do a.array.(i) <- None done) - curves + a.index <- 0; + a.average#set_value 0.; + a.stdev#set_value 0.; + for i = 0 to Array.length a.array - 1 do a.array.(i) <- None done) + curves method set_size = fun new_size -> if new_size <> size && new_size > 0 then begin - Hashtbl.iter (fun _ a -> - let new_array = Array.create new_size None in - for i = 0 to Pervasives.min size new_size - 1 do - new_array.(new_size - 1 - i) <- a.array.((a.index-i+size) mod size) - done; - a.array <- new_array; - a.index <- new_size - 1) - curves; - size <- new_size + Hashtbl.iter (fun _ a -> + let new_array = Array.create new_size None in + for i = 0 to Pervasives.min size new_size - 1 do + new_array.(new_size - 1 - i) <- a.array.((a.index-i+size) mod size) + done; + a.array <- new_array; + a.index <- new_size - 1) + curves; + size <- new_size end - method create_curve = fun (name:string) -> + method create_curve = fun (name:string) binding -> let color = colors.(color_index) in let values = create_values size color in color_index <- (color_index+1) mod Array.length colors; Hashtbl.add curves name values; + Hashtbl.add bindings name binding; values method delete_curve = fun name -> - Hashtbl.remove curves name + Hashtbl.remove curves name; + try (* this try should not be needed *) + let binding = Hashtbl.find bindings name in + Ivy.unbind binding; + Hashtbl.remove bindings name + with _ -> () method add_value = fun name v -> if status <> Stop then - let a = Hashtbl.find curves name in - a.array.(a.index) <- Some v; - if auto_scale then begin - min <- Pervasives.min min v; - max <- Pervasives.max max v - end + let a = Hashtbl.find curves name in + a.array.(a.index) <- Some v; + if auto_scale then begin + min <- Pervasives.min min v; + max <- Pervasives.max max v + end method reset_scale = fun () -> min <- max_float; max <- -. max_float; Hashtbl.iter (* for all curves *) - (fun name a -> - Array.iter (* for all values *) - (function - None -> () - | Some v -> - min <- Pervasives.min min v; - max <- Pervasives.max max v) - a.array) - curves + (fun name a -> + Array.iter (* for all values *) + (function + None -> () + | Some v -> + min <- Pervasives.min min v; + max <- Pervasives.max max v) + a.array) + curves method shift = fun () -> Hashtbl.iter - (fun _ a -> - (* Shift *) - a.index <- (a.index + 1) mod (Array.length a.array); - a.array.(a.index) <- None) - curves + (fun _ a -> + (* Shift *) + a.index <- (a.index + 1) mod (Array.length a.array); + a.array.(a.index) <- None) + curves method update_curves = fun () -> if Hashtbl.length curves > 0 then - try - if status <> Stop then - self#shift (); - if status <> Suspend then - let da = pm#drawing_area in - let {Gtk.width=width; height=height} = da#misc#allocation in - let dr = pm#get_pixmap () in - dr#set_foreground (`NAME "white"); - dr#rectangle ~x:0 ~y:0 ~width ~height ~filled:true (); - let margin = Pervasives.min (height / 10) 20 in + try + if status <> Stop then + self#shift (); + if status <> Suspend then + let da = pm#drawing_area in + let {Gtk.width=width; height=height} = da#misc#allocation in + let dr = pm#get_pixmap () in + dr#set_foreground (`NAME "white"); + dr#rectangle ~x:0 ~y:0 ~width ~height ~filled:true (); + let margin = Pervasives.min (height / 10) 20 in - (* Time Graduations *) - let context = da#misc#create_pango_context in - context#set_font_by_name ("sans " ^ string_of_int (margin/2)); - let layout = context#create_layout in + (* Time Graduations *) + let context = da#misc#create_pango_context in + context#set_font_by_name ("sans " ^ string_of_int (margin/2)); + let layout = context#create_layout in - Pango.Layout.set_text layout "X"; - let (_, h) = Pango.Layout.get_pixel_size layout in + Pango.Layout.set_text layout "X"; + let (_, h) = Pango.Layout.get_pixel_size layout in - let f = fun x y s -> - Pango.Layout.set_text layout s; - let (w, h) = Pango.Layout.get_pixel_size layout in - dr#put_layout ~x ~y:(y-h/2) ~fore:`BLACK layout in + let f = fun x y s -> + Pango.Layout.set_text layout s; + let (w, h) = Pango.Layout.get_pixel_size layout in + dr#put_layout ~x ~y:(y-h/2) ~fore:`BLACK layout in - let t = dt *. float size in - f (width-width/size) (height-h/2) "0"; - f (width/2) (height-h/2) (Printf.sprintf "-%.1fs" (t/.2.)); - f 0 (height-h/2) (Printf.sprintf "-%.1fs" t); + let t = dt *. float size in + f (width-width/size) (height-h/2) "0"; + f (width/2) (height-h/2) (Printf.sprintf "-%.1fs" (t/.2.)); + f 0 (height-h/2) (Printf.sprintf "-%.1fs" t); - (* Y graduations *) - let (min, max) = - if max > min then (min, max) - else let d = abs_float max /. 10. in (max -. d, max +. d) in - let delta = max -. min in + (* Y graduations *) + let (min, max) = + if max > min then (min, max) + else let d = abs_float max /. 10. in (max -. d, max +. d) in + let delta = max -. min in - let dy = float (height-2*margin) /. delta in - let y = fun v -> - height - margin - truncate ((v-.min)*.dy) in + let dy = float (height-2*margin) /. delta in + let y = fun v -> + height - margin - truncate ((v-.min)*.dy) in - let scale = log delta /. log 10. in - let d = 10. ** floor scale in - let u = - if delta < 2.*.d then d/.5. - else if delta < 5.*.d then d/.2. - else d in - let tick_min = min -. mod_float min u in - for i = 0 to truncate (delta/.u) + 1 do - let tick = tick_min +. float i *. u in - f 0 (y tick) (Printf.sprintf "%.*f" (Pervasives.max 0 (2-truncate scale)) tick) - done; + let scale = log delta /. log 10. in + let d = 10. ** floor scale in + let u = + if delta < 2.*.d then d/.5. + else if delta < 5.*.d then d/.2. + else d in + let tick_min = min -. mod_float min u in + for i = 0 to truncate (delta/.u) + 1 do + let tick = tick_min +. float i *. u in + f 0 (y tick) (Printf.sprintf "%.*f" (Pervasives.max 0 (2-truncate scale)) tick) + done; - (* Constants *) - List.iter (fun v -> - dr#set_foreground (`NAME "black"); - dr#lines [(0, y v); (width-width/size, y v)]) - csts; + (* Constants *) + List.iter (fun v -> + dr#set_foreground (`NAME "black"); + dr#lines [(0, y v); (width-width/size, y v)]) + csts; - let margin = 3 in - let title_y = ref margin in - Hashtbl.iter - (fun title a -> - (* Draw and compute average and stdev*) - let curve = ref [] - and sum = ref 0. and sum_squares = ref 0. - and n = ref 0 in - assert (size = Array.length a.array); - let last_value = ref None in - for i = 0 to size - 1 do - let i' = (i+a.index) mod size in - match a.array.(i') with - None -> () - | Some v -> - incr n; - sum := !sum +. v; - sum_squares := !sum_squares +. v *. v; - let x = (i * width) / size in - begin - match !last_value with - Some lv when a.discrete -> - curve := (x, y lv) :: !curve - | _ -> () - end; - curve := (x, y v) :: !curve; - last_value := Some v - done; - if !curve <> [] then begin - dr#set_foreground (`NAME a.color); - dr#lines !curve; - end; - let fn = float !n in - let avg = !sum /. fn in - let stdev = sqrt ((!sum_squares -. fn *. avg *. avg) /. fn) in - set_float_value a.average avg; - set_float_value a.stdev stdev; + let margin = 3 in + let title_y = ref margin in + Hashtbl.iter (fun title a -> + (* Draw and compute average and stdev*) + let curve = ref [] + and sum = ref 0. and sum_squares = ref 0. + and n = ref 0 in + assert (size = Array.length a.array); + let last_value = ref None in + for i = 0 to size - 1 do + let i' = (i+a.index) mod size in + match a.array.(i') with + None -> () + | Some v -> + incr n; + sum := !sum +. v; + sum_squares := !sum_squares +. v *. v; + let x = (i * width) / size in + begin + match !last_value with + Some lv when a.discrete -> + curve := (x, y lv) :: !curve + | _ -> () + end; + curve := (x, y v) :: !curve; + last_value := Some v + done; + if !curve <> [] then begin + dr#set_foreground (`NAME a.color); + dr#lines !curve; + end; + let fn = float !n in + let avg = !sum /. fn in + let stdev = sqrt ((!sum_squares -. fn *. avg *. avg) /. fn) in + set_float_value a.average avg; + set_float_value a.stdev stdev; - (* Title *) - Pango.Layout.set_text layout title; - let (w, h) = Pango.Layout.get_pixel_size layout in - dr#rectangle ~x:(width-h-margin) ~y:!title_y ~width:h ~height:h ~filled:true (); + (* Title *) + Pango.Layout.set_text layout title; + let (w, h) = Pango.Layout.get_pixel_size layout in + dr#rectangle ~x:(width-h-margin) ~y:!title_y ~width:h ~height:h ~filled:true (); - dr#set_foreground `BLACK; - dr#put_layout ~x:(width-2*margin-w-h) ~y:(!title_y) layout; - title_y := !title_y + h + margin) + dr#set_foreground `BLACK; + dr#put_layout ~x:(width-2*margin-w-h) ~y:(!title_y) layout; + title_y := !title_y + h + margin) curves; pm#redraw () - with - exc -> - prerr_endline (Printexc.to_string exc) + with + exc -> + prerr_endline (Printexc.to_string exc) method stop_timer = fun () -> match timer with - None -> () + None -> () | Some t -> GMain.Timeout.remove t method set_update_time = fun delay -> @@ -306,7 +312,7 @@ class plot = fun ~size ~width ~height ~packing () -> method button_press = fun ev -> match GdkEvent.Button.button ev with - 3 -> self#reset_scale (); true + 3 -> self#reset_scale (); true | _ -> false initializer ignore (self#drawing_area#event#add [`BUTTON_PRESS]) @@ -327,7 +333,7 @@ let base_and_index = fun field_descr -> if Str.string_match field_regexp field_descr 0 then ( Str.matched_group 1 field_descr, - int_of_string (Str.matched_group 2 field_descr)) + int_of_string (Str.matched_group 2 field_descr)) else (field_descr, 0) @@ -339,26 +345,32 @@ let rec plot_window = fun window -> (* Register the window *) let oid = plotter#get_oid in - Hashtbl.add windows oid (); + Hashtbl.add windows oid []; ignore (plotter#parse_geometry window.geometry); plotter#set_icon (Some (GdkPixbuf.from_file Env.icon_file)); let vbox = GPack.vbox ~packing:plotter#add () in - let quit = fun () -> GMain.Main.quit (); exit 0 in - - let close = fun () -> - plotter#destroy (); - Hashtbl.remove windows oid; - if Hashtbl.length windows = 0 then - quit () in - - let tooltips = GData.tooltips () in - let menubar = GMenu.menu_bar ~packing:vbox#pack () in let factory = new GMenu.factory menubar in let accel_group = factory#accel_group in let file_menu = factory#add_submenu "Plot" in let file_menu_fact = new GMenu.factory file_menu ~accel_group in + let h = GPack.hbox ~packing:vbox#pack () in + let curves_menu = factory#add_submenu "Curves" in + let curves_menu_fact = new GMenu.factory curves_menu in + let tooltips = GData.tooltips () in + + let width = 900 and height = 200 in + let plot = new plot ~size: !size ~width ~height ~packing:(vbox#pack ~expand:true) () in + + let quit = fun () -> GMain.Main.quit (); exit 0 in + + let close = fun () -> + List.iter (fun c -> plot#delete_curve c) (Hashtbl.find windows oid); + plotter#destroy (); + Hashtbl.remove windows oid; + if Hashtbl.length windows = 0 then + quit () in ignore (file_menu_fact#add_item "New" ~key:GdkKeysyms._N ~callback:(fun () -> plot_window {window with curves=[]})); @@ -369,18 +381,12 @@ let rec plot_window = fun window -> ignore (file_menu_fact#add_separator ()); ignore (file_menu_fact#add_item "Close" ~key:GdkKeysyms._W ~callback:close); ignore (file_menu_fact#add_item "Quit" ~key:GdkKeysyms._Q ~callback:quit); - let curves_menu = factory#add_submenu "Curves" in - let curves_menu_fact = new GMenu.factory curves_menu in tooltips#set_tip reset_item#coerce ~text:"Reset the current display and the current data"; tooltips#set_tip curves_menu#coerce ~text:"Delete the curve"; tooltips#set_tip suspend_item#coerce ~text:"Freeze the display while the data are still updated"; tooltips#set_tip stop_item#coerce ~text:"Freeze the data update while the display is active (e.g. resizable)"; tooltips#set_tip start_item#coerce ~text:"UnFreeze"; - let h = GPack.hbox ~packing:vbox#pack () in - - let width = 900 and height = 200 in - let plot = new plot ~size: !size ~width ~height ~packing:(vbox#pack ~expand:true) () in tooltips#set_tip plot#drawing_area#coerce ~text:"Drop a messages field here to draw it"; ignore (plotter#connect#destroy ~callback:close); @@ -448,8 +454,7 @@ let rec plot_window = fun window -> (* Delete *) let delete_item = submenu_fact#add_item "Delete" in let delete = fun () -> - plot#delete_curve name; - Ivy.unbind binding; + plot#delete_curve name; curves_menu#remove (curve_item :> GMenu.menu_item) in ignore (delete_item#connect#activate ~callback:delete); @@ -471,7 +476,8 @@ let rec plot_window = fun window -> let _item = submenu_fact#add_image_item ~image:stdev_value#coerce ~label:"Stdev" () in let update_stdev_value = fun () -> stdev_value#set_text (sprintf "%.6f" curve.stdev#value) in - ignore (curve.stdev#connect#value_changed update_stdev_value) in + ignore (curve.stdev#connect#value_changed update_stdev_value) + in let add_curve = fun ?(factor=(1.,0.)) name -> let (a, b) = factor in @@ -482,10 +488,9 @@ let rec plot_window = fun window -> let cb = fun _sender values -> let (field_name, index) = base_and_index field_descr in let value = - match Pprz.assoc field_name values with - Pprz.Array array -> - array.(index) - | scalar -> scalar in + match Pprz.assoc field_name values with + Pprz.Array array -> array.(index) + | scalar -> scalar in let float = pprz_float value in let v = float *. a +. b in plot#add_value name v in @@ -493,30 +498,35 @@ let rec plot_window = fun window -> let module P = Pprz.Messages (struct let name = class_name end) in let binding = if sender = "*" then - P.message_bind msg_name cb + P.message_bind msg_name cb else - P.message_bind ~sender msg_name cb in + P.message_bind ~sender msg_name cb in - let curve = plot#create_curve name in - insert_in_menu curve name binding in + let curve = plot#create_curve name binding in + insert_in_menu curve name binding; + + (* store name of the curves associated to a window correct closing *) + let curves_name = Hashtbl.find windows oid in + Hashtbl.replace windows oid (curves_name @ [name]) + in (* Drag and drop handler *) - let data_received = fun context ~x ~y data ~info ~time -> - let factor = Ocaml_tools.affine_transform factor#text in - try - let name = data#data in - add_curve ~factor name - with - exc -> prerr_endline (Printexc.to_string exc) + let data_received = fun context ~x ~y data ~info ~time -> + let factor = Ocaml_tools.affine_transform factor#text in + try + let name = data#data in + add_curve ~factor name + with + exc -> prerr_endline (Printexc.to_string exc) in - plotter#drag#dest_set dnd_targets ~actions:[`COPY]; - ignore (plotter#drag#connect#data_received ~callback:(data_received)); + plotter#drag#dest_set dnd_targets ~actions:[`COPY]; + ignore (plotter#drag#connect#data_received ~callback:(data_received)); - (* Init curves *) - List.iter add_curve window.curves; + (* Init curves *) + List.iter add_curve window.curves; - plotter#add_accel_group accel_group; - plotter#show () + plotter#add_accel_group accel_group; + plotter#show () From b3f1aee620d071d9b07d9397236c6f405378e242 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 2 Mar 2012 12:26:16 +0100 Subject: [PATCH 096/112] added link to github issues to BUGS --- BUGS | 1 + 1 file changed, 1 insertion(+) diff --git a/BUGS b/BUGS index 1cc0f35ac7..ff03a58fd4 100644 --- a/BUGS +++ b/BUGS @@ -1,2 +1,3 @@ We count on your for finding them +Please see the bug/issue tracker on https://github.com/paparazzi/paparazzi/issues \ No newline at end of file From 0540d1e19e8f3fa1a398a8d712b792f3b3630e60 Mon Sep 17 00:00:00 2001 From: Felix Ruess Date: Fri, 2 Mar 2012 17:09:50 +0100 Subject: [PATCH 097/112] removed empty readme --- sw/README | 21 --------------------- 1 file changed, 21 deletions(-) delete mode 100644 sw/README diff --git a/sw/README b/sw/README deleted file mode 100644 index 0bc10093a6..0000000000 --- a/sw/README +++ /dev/null @@ -1,21 +0,0 @@ -# -# $Id$ -# Copyright (C) 2003 Pascal Brisset Antoine Drouin -# -# This file is part of paparazzi. -# -# paparazzi is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 2, or (at your option) -# any later version. -# -# paparazzi is distributed in the hope that it will be useful, -# but WITHOUT ANY WARRANTY; without even the implied warranty of -# MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the -# GNU General Public License for more details. -# -# You should have received a copy of the GNU General Public License -# along with paparazzi; see the file COPYING. If not, write to -# the Free Software Foundation, 59 Temple Place - Suite 330, -# Boston, MA 02111-1307, USA. -# From bfd067a80880826752a26b201009dbc6ce200323 Mon Sep 17 00:00:00 2001 From: Martin Mueller Date: Fri, 2 Mar 2012 22:04:15 +0100 Subject: [PATCH 098/112] add pprz/xbee message format configuration option for logger --- conf/airframes/logger_sd.xml | 1 + conf/autopilot/logger.makefile | 11 +++++++---- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/conf/airframes/logger_sd.xml b/conf/airframes/logger_sd.xml index 68ed0a2db5..7042581ce5 100644 --- a/conf/airframes/logger_sd.xml +++ b/conf/airframes/logger_sd.xml @@ -37,6 +37,7 @@ + diff --git a/conf/autopilot/logger.makefile b/conf/autopilot/logger.makefile index 680131df66..f6e87ecea4 100644 --- a/conf/autopilot/logger.makefile +++ b/conf/autopilot/logger.makefile @@ -34,10 +34,10 @@ ifeq ($(ARCH), lpc21) ap.CFLAGS += -DUSE_LED ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c $(SRC_FIRMWARE)/main_logger.c -#choose one -ap.CFLAGS += -DLOG_XBEE -#ap.CFLAGS += -DLOG_PPRZ - +# PPRZ message format is default +ifndef LOG_MSG_FMT +LOG_MSG_FMT = LOG_PPRZ +endif #set the speed ap.CFLAGS += -DUSE_UART0 -DUART0_BAUD=$(UART0_BAUD) -DUSE_UART0_RX_ONLY @@ -50,6 +50,9 @@ ap.srcs += mcu.c #set SPI interface for SD card (0 or 1) ap.CFLAGS += -DHW_ENDPOINT_LPC2000_SPINUM=$(SPI_CHANNEL) +#message format pprz/xbee +ap.CFLAGS += -D$(LOG_MSG_FMT) + #LPC2148 USB hw module needs at least 18MHz PCLK ap.CFLAGS += -DUSE_USB_HIGH_PCLK From a2406516c0b6ca33c7634043fa25318c3f00d669 Mon Sep 17 00:00:00 2001 From: Christoph Niemann Date: Sat, 3 Mar 2012 10:49:34 +0100 Subject: [PATCH 099/112] Add OpenLog Module --- conf/messages.xml | 4 +++- sw/logalizer/Makefile | 11 +++++++++-- 2 files changed, 12 insertions(+), 3 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index fd43ca95d8..d8d5363da9 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -941,7 +941,9 @@ - + + + diff --git a/sw/logalizer/Makefile b/sw/logalizer/Makefile index 71d397db08..185058bc34 100644 --- a/sw/logalizer/Makefile +++ b/sw/logalizer/Makefile @@ -27,7 +27,7 @@ OCAMLC = ocamlc OCAMLOPT = ocamlopt INCLUDES= $(shell ocamlfind query -r -i-format xml-light) $(shell ocamlfind query -r -i-format lablgtk2) -I ../lib/ocaml -all: play plotter plot sd2log plotprofile +all: play plotter plot sd2log plotprofile openlog2tlm play : log_file.cmo play_core.cmo play.cmo @echo OL $@ @@ -49,6 +49,13 @@ sd2log : sd2log.cmo @echo OL $@ $(Q)$(OCAMLC) $(INCLUDES) -custom -o $@ unix.cma str.cma xml-light.cma glibivy-ocaml.cma lib-pprz.cma $^ +CC = gcc +CFLAGS=-g -O2 -Wall +LDFLAGS= + +openlog2tlm: openlog2tlm.c + $(CC) $(CFLAGS) -g -o $@ $^ + play play-nox plotter sd2log : ../lib/ocaml/lib-pprz.cma plot : ../lib/ocaml/lib-pprz.cmxa @@ -115,7 +122,7 @@ test3: test3.c sliding_plot.c $(CC) $(CFLAGS) -g -o $@ $^ $(LDFLAGS) clean: - rm -f *.opt *.out *~ core *.o *.bak .depend *.cm* play ahrsview imuview ahrs2fg plot plotter gtk_export.ml + rm -f *.opt *.out *~ core *.o *.bak .depend *.cm* play ahrsview imuview ahrs2fg plot plotter gtk_export.ml openlog2tlm #FGFS_PREFIX=/home/poine/local FGFS_PREFIX=/home/poine/flightgear From 60cf321a592895bb05ec456f051acfe8c0d573ca Mon Sep 17 00:00:00 2001 From: Christoph Niemann Date: Sat, 3 Mar 2012 11:01:39 +0100 Subject: [PATCH 100/112] Oops, missed some files --- conf/airframes/microjet_example.xml | 1 + conf/modules/openlog.xml | 16 ++++ sw/airborne/modules/openlog/openlog.c | 49 +++++++++++++ sw/airborne/modules/openlog/openlog.h | 38 ++++++++++ sw/logalizer/openlog2tlm.c | 101 ++++++++++++++++++++++++++ 5 files changed, 205 insertions(+) create mode 100755 conf/modules/openlog.xml create mode 100755 sw/airborne/modules/openlog/openlog.c create mode 100755 sw/airborne/modules/openlog/openlog.h create mode 100755 sw/logalizer/openlog2tlm.c diff --git a/conf/airframes/microjet_example.xml b/conf/airframes/microjet_example.xml index ec56ab56e9..62174e71f2 100644 --- a/conf/airframes/microjet_example.xml +++ b/conf/airframes/microjet_example.xml @@ -190,6 +190,7 @@ + diff --git a/conf/modules/openlog.xml b/conf/modules/openlog.xml new file mode 100755 index 0000000000..3123fceb7e --- /dev/null +++ b/conf/modules/openlog.xml @@ -0,0 +1,16 @@ + + + +
+ +
+ + + + +#Exemple of RAW makefile part + + + +
+ diff --git a/sw/airborne/modules/openlog/openlog.c b/sw/airborne/modules/openlog/openlog.c new file mode 100755 index 0000000000..327ab49ec4 --- /dev/null +++ b/sw/airborne/modules/openlog/openlog.c @@ -0,0 +1,49 @@ +/* + * $Id$ + * + * Copyright (C) 2011 Christoph Niemann + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/* + * This module provides a timestamp-message, allowing + * sw/logalizer/openlog2tlm to convert a recorded dumpfile, + * created by openlog into the pprz-tlm format, to be converted into + * .data and .log files by sw/logalizer/sd2log + */ + +#include "openlog.h" +#include "messages.h" +#include "downlink.h" +#include "mcu_periph/uart.h" + +#ifndef DOWNLINK_DEVICE +#define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE +#endif + +uint32_t timestamp = 0; //max flighttime = 49 days :-) + +void init_openlog(void) { +} + +void periodic_2Hz_openlog(void) { + timestamp=timestamp+500; + DOWNLINK_SEND_OPENLOG_TIMESTAMP(DefaultChannel, ×tamp); +} diff --git a/sw/airborne/modules/openlog/openlog.h b/sw/airborne/modules/openlog/openlog.h new file mode 100755 index 0000000000..9c86ba49ca --- /dev/null +++ b/sw/airborne/modules/openlog/openlog.h @@ -0,0 +1,38 @@ +/* + * $Id$ + * + * Copyright (C) 2011 Christoph Niemann + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + */ + +/** \file openlog.h + * This module provides a timestamp-message, allowing + * sw/logalizer/openlog2tlm to convert a recorded dumpfile, + * created by openlog into the pprz-tlm format, to be converted into + * .data and .log files by sw/logalizer/sd2log + */ + +#ifndef OPENLOG_H +#define OPENLOG_H + +void init_openlog(void); +void periodic_2Hz_openlog(void); + +#endif diff --git a/sw/logalizer/openlog2tlm.c b/sw/logalizer/openlog2tlm.c new file mode 100755 index 0000000000..9160b82bbf --- /dev/null +++ b/sw/logalizer/openlog2tlm.c @@ -0,0 +1,101 @@ +/* + * $Id$ + * + * Log player + * + * Copyright (C) 2011 Christoph Niemann + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + * + * + Description : Converts a Paparazzi Message dump, containing a timestamp, + to Paparazzi TLM, wich can be converted to .data and .log by + sw/logalizer/sd2log + + The openlog Module has to be loaded for use + */ + +#include +#include + +//define the message id for the OPENLOG_TIMESTAMP message (default is 59) +#define MSG_NUMBER 59 + +int main(int argc, char *argv[]) { + FILE *in,*out; + + int current_timestamp = 0; + int timestamp_bytes[4] = {0,0,0,0}; + int temp = 0; + + if(argc != 3){ + puts("wrong number of parameters!\n" + "usage is openlog2tlm "); + return EXIT_FAILURE; + } + if((in=fopen(argv[1],"rb"))==NULL){ + puts("openlog2tlm wasn't able to open the inputfile\n"); + return EXIT_FAILURE; + } + if((out=fopen(argv[2],"wb"))==NULL){ + puts("openlog2tlm wasn't able to open the outputfile\n"); + return EXIT_FAILURE; + } + + printf("converting %s to %s\n",argv[1],argv[2]); + + temp = fgetc(in); + + while(!feof(in)){ + if(temp==0x99){//if a message starts + int length=fgetc(in); //determining the length of the message + int message[length-2]; // allocate an array that fits for the message + int i; + for(i = 0; i<(length-2); i++){//read the complete message first + message[i]=fgetc(in); + } + temp = fgetc(in); + if(message[1]==MSG_NUMBER){ + current_timestamp = message[2]+(message[3]<<8)+(message[4]<<16)+(message[5]<<24); + //printf("hooray openlog message! the time is %i now (in ms)\n", current_timestamp); + current_timestamp = current_timestamp*10; //now according to 100 microsecond grid for tlm + //splitting the timestamp into bytes again, to use it for the messages + timestamp_bytes[0] = current_timestamp & 0xff; + timestamp_bytes[1] = ( current_timestamp >> 8 ) & 0xff; + timestamp_bytes[2] = ( current_timestamp >> 16 ) & 0xff; + timestamp_bytes[3] = ( current_timestamp >> 24 ) & 0xff; + } + //start to write the message to the tlm-file + fputc(0x99,out);//write PPRZ_STX + fputc(length-4,out);//write LENGTH, recalculated for TLM + fputc(0,out); //write SOURCE, defaults to uart0 + fputc(timestamp_bytes[0],out); //write TIMESTAMP_LSB + fputc(timestamp_bytes[1],out); //write TIMESTAMP + fputc(timestamp_bytes[2],out); //write TIMESTAMP + fputc(timestamp_bytes[3],out); //write TIMESTAMP_MSB + int checksum = length-4+timestamp_bytes[0]+timestamp_bytes[1]+timestamp_bytes[2]+timestamp_bytes[3]; + for(i = 0; i<(length-4); i++){//write payload + fputc(message[i],out); + checksum+=message[i]; + } + fputc(checksum,out);//write checksum, recalculated for tlm + } + } + return EXIT_SUCCESS; +} + From 1503228e3954ba5f7a310673689e0ee0498bd630 Mon Sep 17 00:00:00 2001 From: Christoph Niemann Date: Sat, 3 Mar 2012 11:08:45 +0100 Subject: [PATCH 101/112] Alter the MSG number according to messages.xml --- sw/logalizer/openlog2tlm.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/logalizer/openlog2tlm.c b/sw/logalizer/openlog2tlm.c index 9160b82bbf..f9ccce0878 100755 --- a/sw/logalizer/openlog2tlm.c +++ b/sw/logalizer/openlog2tlm.c @@ -1,7 +1,7 @@ /* * $Id$ * - * Log player + * Converter for OpenLog logfiles to TLM * * Copyright (C) 2011 Christoph Niemann * @@ -34,7 +34,7 @@ #include //define the message id for the OPENLOG_TIMESTAMP message (default is 59) -#define MSG_NUMBER 59 +#define MSG_NUMBER 129 int main(int argc, char *argv[]) { FILE *in,*out; From 6e95d4c8b3cc43c01ffbd4b520488a1369e1ed61 Mon Sep 17 00:00:00 2001 From: Christoph Niemann Date: Sat, 3 Mar 2012 11:08:45 +0100 Subject: [PATCH 102/112] x. --- sw/logalizer/openlog2tlm.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/sw/logalizer/openlog2tlm.c b/sw/logalizer/openlog2tlm.c index 9160b82bbf..f9ccce0878 100755 --- a/sw/logalizer/openlog2tlm.c +++ b/sw/logalizer/openlog2tlm.c @@ -1,7 +1,7 @@ /* * $Id$ * - * Log player + * Converter for OpenLog logfiles to TLM * * Copyright (C) 2011 Christoph Niemann * @@ -34,7 +34,7 @@ #include //define the message id for the OPENLOG_TIMESTAMP message (default is 59) -#define MSG_NUMBER 59 +#define MSG_NUMBER 129 int main(int argc, char *argv[]) { FILE *in,*out; From 470599265e415dfa35b121fe8c5a3acf832eef64 Mon Sep 17 00:00:00 2001 From: Christoph Niemann Date: Sat, 3 Mar 2012 23:56:26 +0100 Subject: [PATCH 103/112] Improved code style and added Doxygen --- conf/messages.xml | 2 +- conf/modules/openlog.xml | 3 - sw/airborne/modules/openlog/openlog.c | 6 +- sw/logalizer/openlog2tlm.c | 126 +++++++++++++------------- 4 files changed, 66 insertions(+), 71 deletions(-) diff --git a/conf/messages.xml b/conf/messages.xml index d8d5363da9..982ce3b37f 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -941,7 +941,7 @@ - + diff --git a/conf/modules/openlog.xml b/conf/modules/openlog.xml index 3123fceb7e..5f23717266 100755 --- a/conf/modules/openlog.xml +++ b/conf/modules/openlog.xml @@ -7,9 +7,6 @@ - -#Exemple of RAW makefile part - diff --git a/sw/airborne/modules/openlog/openlog.c b/sw/airborne/modules/openlog/openlog.c index 327ab49ec4..3b62e2aa14 100755 --- a/sw/airborne/modules/openlog/openlog.c +++ b/sw/airborne/modules/openlog/openlog.c @@ -22,7 +22,7 @@ * */ -/* +/** * This module provides a timestamp-message, allowing * sw/logalizer/openlog2tlm to convert a recorded dumpfile, * created by openlog into the pprz-tlm format, to be converted into @@ -38,12 +38,12 @@ #define DOWNLINK_DEVICE DOWNLINK_AP_DEVICE #endif -uint32_t timestamp = 0; //max flighttime = 49 days :-) +uint32_t timestamp = 0; ///< Timestamp to be incremented during operation void init_openlog(void) { } void periodic_2Hz_openlog(void) { timestamp=timestamp+500; - DOWNLINK_SEND_OPENLOG_TIMESTAMP(DefaultChannel, ×tamp); + DOWNLINK_SEND_TIMESTAMP(DefaultChannel, ×tamp); } diff --git a/sw/logalizer/openlog2tlm.c b/sw/logalizer/openlog2tlm.c index f9ccce0878..72bfea4e62 100755 --- a/sw/logalizer/openlog2tlm.c +++ b/sw/logalizer/openlog2tlm.c @@ -22,80 +22,78 @@ * the Free Software Foundation, 59 Temple Place - Suite 330, * Boston, MA 02111-1307, USA. * - * - Description : Converts a Paparazzi Message dump, containing a timestamp, - to Paparazzi TLM, wich can be converted to .data and .log by - sw/logalizer/sd2log - - The openlog Module has to be loaded for use */ +/** Converts a Paparazzi Message dump, containing a timestamp, + to Paparazzi TLM, wich can be converted to .data and .log by + sw/logalizer/sd2log . + The openlog Module has to be loaded for use +*/ + #include #include -//define the message id for the OPENLOG_TIMESTAMP message (default is 59) +/* define the message id for the TIMESTAMP message (default is 129) */ #define MSG_NUMBER 129 int main(int argc, char *argv[]) { - FILE *in,*out; + FILE *in,*out; - int current_timestamp = 0; - int timestamp_bytes[4] = {0,0,0,0}; - int temp = 0; + int current_timestamp = 0; + int timestamp_bytes[4] = {0,0,0,0}; + int temp = 0; - if(argc != 3){ - puts("wrong number of parameters!\n" - "usage is openlog2tlm "); - return EXIT_FAILURE; - } - if((in=fopen(argv[1],"rb"))==NULL){ - puts("openlog2tlm wasn't able to open the inputfile\n"); - return EXIT_FAILURE; - } - if((out=fopen(argv[2],"wb"))==NULL){ - puts("openlog2tlm wasn't able to open the outputfile\n"); - return EXIT_FAILURE; - } + if(argc != 3){ + puts("wrong number of parameters!\n" + "usage is openlog2tlm "); + return EXIT_FAILURE; + } + if((in=fopen(argv[1],"rb"))==NULL){ + puts("openlog2tlm wasn't able to open the inputfile\n"); + return EXIT_FAILURE; + } + if((out=fopen(argv[2],"wb"))==NULL){ + puts("openlog2tlm wasn't able to open the outputfile\n"); + return EXIT_FAILURE; + } - printf("converting %s to %s\n",argv[1],argv[2]); + printf("converting %s to %s\n",argv[1],argv[2]); - temp = fgetc(in); - - while(!feof(in)){ - if(temp==0x99){//if a message starts - int length=fgetc(in); //determining the length of the message - int message[length-2]; // allocate an array that fits for the message - int i; - for(i = 0; i<(length-2); i++){//read the complete message first - message[i]=fgetc(in); - } - temp = fgetc(in); - if(message[1]==MSG_NUMBER){ - current_timestamp = message[2]+(message[3]<<8)+(message[4]<<16)+(message[5]<<24); - //printf("hooray openlog message! the time is %i now (in ms)\n", current_timestamp); - current_timestamp = current_timestamp*10; //now according to 100 microsecond grid for tlm - //splitting the timestamp into bytes again, to use it for the messages - timestamp_bytes[0] = current_timestamp & 0xff; - timestamp_bytes[1] = ( current_timestamp >> 8 ) & 0xff; - timestamp_bytes[2] = ( current_timestamp >> 16 ) & 0xff; - timestamp_bytes[3] = ( current_timestamp >> 24 ) & 0xff; - } - //start to write the message to the tlm-file - fputc(0x99,out);//write PPRZ_STX - fputc(length-4,out);//write LENGTH, recalculated for TLM - fputc(0,out); //write SOURCE, defaults to uart0 - fputc(timestamp_bytes[0],out); //write TIMESTAMP_LSB - fputc(timestamp_bytes[1],out); //write TIMESTAMP - fputc(timestamp_bytes[2],out); //write TIMESTAMP - fputc(timestamp_bytes[3],out); //write TIMESTAMP_MSB - int checksum = length-4+timestamp_bytes[0]+timestamp_bytes[1]+timestamp_bytes[2]+timestamp_bytes[3]; - for(i = 0; i<(length-4); i++){//write payload - fputc(message[i],out); - checksum+=message[i]; - } - fputc(checksum,out);//write checksum, recalculated for tlm - } - } - return EXIT_SUCCESS; -} + temp = fgetc(in); + while(!feof(in)){ + if(temp==0x99){/// if a message starts + int length=fgetc(in); /// determining the length of the message + int message[length-2]; /// allocate an array that fits for the message + int i; + for(i = 0; i<(length-2); i++){/// read the complete message first + message[i]=fgetc(in); + } + temp = fgetc(in); + if(message[1]==MSG_NUMBER){ + current_timestamp = message[2]+(message[3]<<8)+(message[4]<<16)+(message[5]<<24); + current_timestamp = current_timestamp*10; /// now according to 100 microsecond grid for tlm + /// splitting the timestamp into bytes again, to use it for the messages + timestamp_bytes[0] = current_timestamp & 0xff; + timestamp_bytes[1] = ( current_timestamp >> 8 ) & 0xff; + timestamp_bytes[2] = ( current_timestamp >> 16 ) & 0xff; + timestamp_bytes[3] = ( current_timestamp >> 24 ) & 0xff; + } + /// start to write the message to the tlm-file + fputc(0x99,out);/// write PPRZ_STX + fputc(length-4,out);/// write LENGTH, recalculated for TLM + fputc(0,out); /// write SOURCE, defaults to uart0 + fputc(timestamp_bytes[0],out); /// write TIMESTAMP_LSB + fputc(timestamp_bytes[1],out); /// write TIMESTAMP + fputc(timestamp_bytes[2],out); /// write TIMESTAMP + fputc(timestamp_bytes[3],out); /// write TIMESTAMP_MSB + int checksum = length-4+timestamp_bytes[0]+timestamp_bytes[1]+timestamp_bytes[2]+timestamp_bytes[3]; + for(i = 0; i<(length-4); i++){/// write payload + fputc(message[i],out); + checksum+=message[i]; + } + fputc(checksum,out);/// write checksum, recalculated for tlm + } + } + return EXIT_SUCCESS; +} \ No newline at end of file From a68ac23d3a7783de9c66bd8e586e7ca9cd5c62c2 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 14:30:50 +0100 Subject: [PATCH 104/112] Remove files to solve continuous merge conflicts: please refer to tudelft/paparazzi for updated airframe files --- .../yapa_xsens.xml => CDW/LisaAspirin2.xml} | 161 +++++---- conf/airframes/CDW/yapa3_aspirin2.xml | 274 +++++++++++++++ .../TU_Delft/EasyStartPanTiltCHIMU_SPI.xml | 200 ----------- conf/airframes/TU_Delft/MicrojetBR.xml | 274 --------------- conf/airframes/TU_Delft/MicrojetBRimu.xml | 307 ----------------- conf/airframes/TU_Delft/MicrojetCDW.xml | 231 ------------- conf/airframes/TU_Delft/Trip50A.xml | 297 ---------------- conf/airframes/TU_Delft/Trip50B.xml | 313 ----------------- conf/airframes/TU_Delft/holiday50.xml | 313 ----------------- conf/airframes/TU_Delft/skywalker.xml | 244 ------------- conf/airframes/TU_Delft/skywalkerfiber.xml | 326 ------------------ 11 files changed, 366 insertions(+), 2574 deletions(-) rename conf/airframes/{TU_Delft/yapa_xsens.xml => CDW/LisaAspirin2.xml} (65%) create mode 100644 conf/airframes/CDW/yapa3_aspirin2.xml delete mode 100644 conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml delete mode 100644 conf/airframes/TU_Delft/MicrojetBR.xml delete mode 100644 conf/airframes/TU_Delft/MicrojetBRimu.xml delete mode 100644 conf/airframes/TU_Delft/MicrojetCDW.xml delete mode 100644 conf/airframes/TU_Delft/Trip50A.xml delete mode 100644 conf/airframes/TU_Delft/Trip50B.xml delete mode 100644 conf/airframes/TU_Delft/holiday50.xml delete mode 100644 conf/airframes/TU_Delft/skywalker.xml delete mode 100644 conf/airframes/TU_Delft/skywalkerfiber.xml diff --git a/conf/airframes/TU_Delft/yapa_xsens.xml b/conf/airframes/CDW/LisaAspirin2.xml similarity index 65% rename from conf/airframes/TU_Delft/yapa_xsens.xml rename to conf/airframes/CDW/LisaAspirin2.xml index daf296a3c2..807bd309d8 100644 --- a/conf/airframes/TU_Delft/yapa_xsens.xml +++ b/conf/airframes/CDW/LisaAspirin2.xml @@ -1,15 +1,15 @@ - + - - - + + + @@ -28,53 +28,58 @@ -
- - - - - - - - - - - - - - - -
- - - - - - - - - - - - - - - - + + - - - + + +
+ + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + +
+
@@ -88,11 +93,6 @@
-
- - -
-
@@ -177,40 +177,62 @@ - - - - + - - - - + --> + + + - + - - + + + + + + + + + + + + + + + + + + + + - + @@ -218,9 +240,10 @@ - + + diff --git a/conf/airframes/CDW/yapa3_aspirin2.xml b/conf/airframes/CDW/yapa3_aspirin2.xml new file mode 100644 index 0000000000..7696df9c4a --- /dev/null +++ b/conf/airframes/CDW/yapa3_aspirin2.xml @@ -0,0 +1,274 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ + + +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
+ +
+ + +
+ +
+ + +
+ +
+ + + + + +
+ +
+ + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + + + + + + + + + + +
+ +
+ + + + + + + + +
+ +
+ + + + + + + +
+ +
+ + +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
diff --git a/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml b/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml deleted file mode 100644 index 96d2fce242..0000000000 --- a/conf/airframes/TU_Delft/EasyStartPanTiltCHIMU_SPI.xml +++ /dev/null @@ -1,200 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- -
- - -
- -
- - - - - - - - - -
- -
- - - -
- -
- - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - -
- -
- - - - - - - - -
- -
- - - - - - - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/conf/airframes/TU_Delft/MicrojetBR.xml b/conf/airframes/TU_Delft/MicrojetBR.xml deleted file mode 100644 index 117bc78989..0000000000 --- a/conf/airframes/TU_Delft/MicrojetBR.xml +++ /dev/null @@ -1,274 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- - - - - - - - - - - - -
- - -
- -
- - - - - - - - - - - - - - - - - - - - -
- - -
- - - - - - -
- -
- - -
- -
- - - - - - - - - - - - - - - - -
- -
- - - -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - -
- -
- - - - - - - - -
- -
- - - - - -
- -
- - - - - - - - - -
- - -
- - - - -
- -
- - - -
- -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/conf/airframes/TU_Delft/MicrojetBRimu.xml b/conf/airframes/TU_Delft/MicrojetBRimu.xml deleted file mode 100644 index 681291c9d6..0000000000 --- a/conf/airframes/TU_Delft/MicrojetBRimu.xml +++ /dev/null @@ -1,307 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- - - - - - - - - - - - - -
- - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - -
- -
- - -
- -
- - -
- -
- - - - - - - - - - - - - - - - -
- -
- - - -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - -
- -
- - - - - - - - -
- -
- - - - - -
- -
- - - - - - - - - -
- - -
- - - - -
- -
- - - -
- -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/conf/airframes/TU_Delft/MicrojetCDW.xml b/conf/airframes/TU_Delft/MicrojetCDW.xml deleted file mode 100644 index a778aeb5ff..0000000000 --- a/conf/airframes/TU_Delft/MicrojetCDW.xml +++ /dev/null @@ -1,231 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- - - - - - - - - - -
- - -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - -
- -
- - -
- -
- - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - -
- -
- - - - - - - - -
- -
- - - - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/conf/airframes/TU_Delft/Trip50A.xml b/conf/airframes/TU_Delft/Trip50A.xml deleted file mode 100644 index a37429aeb5..0000000000 --- a/conf/airframes/TU_Delft/Trip50A.xml +++ /dev/null @@ -1,297 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - -
- -
- - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - -
- - -
- - - - - - - - - -
- -
- - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - -
- -
- - - -
- -
- - - - - - - - -
- -
- - - - -
- -
- -
- - -CONFIG = \"tiny_sense.h\" - -include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile - -FLASH_MODE=IAP - -ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=2 -ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c - -ap.srcs += commands.c - -ap.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -ap.srcs += $(SRC_ARCH)/servos_4017_hw.c actuators.c - -ap.CFLAGS += -DRADIO_CONTROL -ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c - -#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600 -#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c - -#TRANSPARENT -#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -#DDATALINK=PPRZ -DUART1_BAUD=B9600 -#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c - -# Maxstream API protocol -ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B9600 -ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c - -ap.CFLAGS += -DINTER_MCU -ap.srcs += inter_mcu.c - -ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 -DUSE_ADC_3 -DUSE_ADC_4 -DUSE_ADC_5 -DUSE_GYRO -DIDG300 -ap.srcs += $(SRC_ARCH)/adc_hw.c - -ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART0 -DGPS_LINK=Uart0 -DUART0_BAUD=B38400 -DGPS_USE_LATLONG -ap.srcs += gps_ubx.c gps.c latlong.c - -ap.CFLAGS += -DUSE_INFRARED -DALT_KALMAN -DWIND_INFO -DWIND_INFO_RET -DSTRONG_WIND -ap.srcs += infrared.c estimator.c gyro.c - -ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM -ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c - -ap.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c - -#ap.srcs += baro_bmp.c $(SRC_ARCH)/i2c_hw.c i2c.c -#ap.CFLAGS += -DUSE_I2C0 -DUSE_BARO_BMP -DBARO_BMP_ACCEL - -# Config for SITL simulation -include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile -sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN -sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c - -sim.srcs += joystick.c -sim.CFLAGS += -DUSE_JOYSTICK - - - -
diff --git a/conf/airframes/TU_Delft/Trip50B.xml b/conf/airframes/TU_Delft/Trip50B.xml deleted file mode 100644 index a95827c333..0000000000 --- a/conf/airframes/TU_Delft/Trip50B.xml +++ /dev/null @@ -1,313 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - -
- -
- - -
- -
- - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - -
- - -
- - - - - - - - - -
- -
- - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - -
- -
- - - -
- -
- - - - - - - - -
- -
- - - - -
- -
- -
- - -CONFIG = \"tiny_sense.h\" - -include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile - -FLASH_MODE=IAP - -ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=$(CONFIG) -DUSE_LED -DTIME_LED=2 -ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c - -ap.srcs += commands.c - -ap.CFLAGS += -DACTUATORS=\"servos_4017_hw.h\" -DSERVOS_4017 -ap.srcs += $(SRC_ARCH)/servos_4017_hw.c actuators.c - -ap.CFLAGS += -DRADIO_CONTROL -ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c - -#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B57600 -#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c - -#TRANSPARENT -#ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DPPRZ_UART=Uart1 -#DDATALINK=PPRZ -DUART1_BAUD=B9600 -#ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c - -# Maxstream API protocol -ap.CFLAGS += -DDOWNLINK -DUSE_UART1 -DDOWNLINK_TRANSPORT=XBeeTransport -DDOWNLINK_FBW_DEVICE=Uart1 -DDOWNLINK_AP_DEVICE=Uart1 -DXBEE_UART=Uart1 -DDATALINK=XBEE -DUART1_BAUD=B9600 -ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c xbee.c - -ap.CFLAGS += -DINTER_MCU -ap.srcs += inter_mcu.c - -ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 -DUSE_ADC_3 -DUSE_ADC_4 -DUSE_ADC_5 -DUSE_GYRO -DIDG300 -ap.srcs += $(SRC_ARCH)/adc_hw.c - -ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART0 -DGPS_LINK=Uart0 -DUART0_BAUD=B38400 -DGPS_USE_LATLONG -ap.srcs += gps_ubx.c gps.c latlong.c - -ap.CFLAGS += -DUSE_INFRARED -DALT_KALMAN -DWIND_INFO -DWIND_INFO_RET -DSTRONG_WIND -ap.srcs += infrared.c estimator.c gyro.c - -ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM -ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c - -ap.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c - -ap.srcs += baro_bmp.c $(SRC_ARCH)/i2c_hw.c i2c.c -ap.CFLAGS += -DUSE_I2C0 -DUSE_BARO_BMP -DBARO_BMP_ACCEL - -# camera control -ap.CFLAGS += -DCAM -DMOBILE_CAM -DPOINT_CAM -DPOINT_CAM_PITCH_ROLL -ap.srcs += cam.c point.c - -# Config for SITL simulation -include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile -sim.CFLAGS += -DBOARD_CONFIG=\"tiny.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN -sim.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c - -sim.srcs += joystick.c -sim.CFLAGS += -DUSE_JOYSTICK - -sim.CFLAGS += -DCAM -DMOBILE_CAM -DPOINT_CAM -DPOINT_CAM_PITCH_ROLL -# -DTEST_CAM -sim.srcs += cam.c point.c -sim.srcs += subsystems/navigation/bomb.c - - - - - -
diff --git a/conf/airframes/TU_Delft/holiday50.xml b/conf/airframes/TU_Delft/holiday50.xml deleted file mode 100644 index 5a2724fbdb..0000000000 --- a/conf/airframes/TU_Delft/holiday50.xml +++ /dev/null @@ -1,313 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - -
- -
- - -
- -
- - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - -
- -
- - - - - -
- - -
- - - - - - - - -
- -
- - - - -
- -
- - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - -
- -
- - - -
- -
- - - - - - - - -
- -
- - - - -
- -
- -
- - -include $(PAPARAZZI_SRC)/conf/autopilot/tiny.makefile - -FLASH_MODE=IAP - -# main files (including the 60Hz timing) -ap.CFLAGS += -DFBW -DAP -DBOARD_CONFIG=\"tiny_1_1.h\" -DUSE_LED -DTIME_LED=1 -ap.srcs = sys_time.c $(SRC_ARCH)/sys_time_hw.c $(SRC_ARCH)/armVIC.c main_fbw.c main_ap.c main.c - -# Command allocation and Radio Mixers -ap.srcs += commands.c - -# Actuators: tiny1.1 board has 4015_MAT servos -ap.CFLAGS += -DACTUATORS=\"servos_4015_MAT_hw.h\" -DSERVOS_4015_MAT -ap.srcs += $(SRC_ARCH)/servos_4015_MAT_hw.c actuators.c - -# 35MHz Radio -ap.CFLAGS += -DRADIO_CONTROL -ap.srcs += radio_control.c $(SRC_ARCH)/ppm_hw.c - -# Paparazzi protocol on UART0 at 57600 -ap.CFLAGS += -DDOWNLINK -DUSE_UART0 -DDOWNLINK_TRANSPORT=PprzTransport -DDOWNLINK_FBW_DEVICE=Uart0 -DDOWNLINK_AP_DEVICE=Uart0 -DPPRZ_UART=Uart0 -DDATALINK=PPRZ -DUART0_BAUD=B57600 -ap.srcs += downlink.c $(SRC_ARCH)/mcu_periph/uart_arch.c datalink.c pprz_transport.c - -# communication from FBW and AP -ap.CFLAGS += -DINTER_MCU -ap.srcs += inter_mcu.c - - -ap.CFLAGS += -DADC -DUSE_ADC_0 -DUSE_ADC_1 -DUSE_ADC_2 -DUSE_ADC_3 -DUSE_ADC_4 -DUSE_ADC_5 -ap.srcs += $(SRC_ARCH)/adc_hw.c - -# USE_GPS on UART1 -ap.CFLAGS += -DUSE_GPS -DUBX -DUSE_UART1 -DGPS_LINK=Uart1 -DUART1_BAUD=B38400 -#ap.CFLAGS += -DGPS_CONFIGURE -DGPS_BAUD=38400 -ap.srcs += gps_ubx.c gps.c latlong.c - -ap.CFLAGS += -DUSE_INFRARED -ap.srcs += infrared.c estimator.c - -ap.CFLAGS += -DNAV -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN -ap.srcs += subsystems/nav.c fw_h_ctl.c fw_v_ctl.c -ap.CFLAGS += -DTUNE_AGRESSIVE_CLIMB - -ap.CFLAGS += -DUSE_GYRO -DADXRS150 -ap.srcs += gyro.c - -ap.CFLAGS += -DUSE_MODULES - -ap.srcs += subsystems/navigation/nav_line.c subsystems/navigation/nav_survey_rectangle.c -ap.srcs += subsystems/navigation/traffic_info.c - -# camera control -ap.CFLAGS += -DCAM -DMOBILE_CAM -DPOINT_CAM -DPOINT_CAM_PITCH_ROLL -# -DTEST_CAM -ap.srcs += cam.c point.c -# subsystems/navigation/traffic_info.c - -ap.CFLAGS += -DWIND_INFO -DSTRONG_WIND -ap.srcs += subsystems/navigation/bomb.c - -# Config for SITL simulation -include $(PAPARAZZI_SRC)/conf/autopilot/sitl.makefile -sim.CFLAGS += -DBOARD_CONFIG=\"tiny_1_1.h\" -DAGR_CLIMB -DLOITER_TRIM -DALT_KALMAN -DWIND_INFO -DSTRONG_WIND -sim.srcs += subsystems/navigation/nav_survey_rectangle.c subsystems/navigation/nav_line.c -sim.CFLAGS += -DTUNE_AGRESSIVE_CLIMB -# subsystems/navigation/traffic_info.c -sim.CFLAGS += -DUSE_MODULES - -sim.CFLAGS += -DCAM -DMOBILE_CAM -DPOINT_CAM -DPOINT_CAM_PITCH_ROLL -# -DTEST_CAM -sim.srcs += cam.c point.c -sim.srcs += subsystems/navigation/bomb.c - - -
diff --git a/conf/airframes/TU_Delft/skywalker.xml b/conf/airframes/TU_Delft/skywalker.xml deleted file mode 100644 index 6b7b00e008..0000000000 --- a/conf/airframes/TU_Delft/skywalker.xml +++ /dev/null @@ -1,244 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - - - - - - - - - - - - - - - -
- - - - - - - - - - - - - - - - - - - - - - - - -
- - - -
- -
- - - -
- -
- - -
- -
- - - - - -
- -
- - -
- -
- - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - - -
- -
- - - - - - - - - - - - - - - - - -
- -
- - - - - - - - -
- -
- - - - - - - -
- -
- - -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
diff --git a/conf/airframes/TU_Delft/skywalkerfiber.xml b/conf/airframes/TU_Delft/skywalkerfiber.xml deleted file mode 100644 index a962c1f226..0000000000 --- a/conf/airframes/TU_Delft/skywalkerfiber.xml +++ /dev/null @@ -1,326 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- - - - - - - - - - - - - - - - - - -
- - - - - - - - - - - - - - - - - - - - - - - - -
- - - -
- -
- - -
- -
- - - - - - - -
- -
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
- - -
- -
- - - - - - - - - - - - - - - - -
- - -
- - - - - - - - - - - - - - - - - - -
- - - -
- - - - - - - - - - - - - - - - - -
- - -
- - - - - - - - -
- - -
- - - - - - - -
- - -
- - -
- -
From c72a42116f80d235842fa674b74d6dcdd9b18383 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:04:41 +0100 Subject: [PATCH 105/112] Run XSens as a module instead --- sw/airborne/modules/ins/ins_xsens.c | 17 ++++++++++++++++- sw/airborne/modules/ins/ins_xsens.h | 7 +++++++ 2 files changed, 23 insertions(+), 1 deletion(-) diff --git a/sw/airborne/modules/ins/ins_xsens.c b/sw/airborne/modules/ins/ins_xsens.c index cce76a36ac..8411e3d474 100644 --- a/sw/airborne/modules/ins/ins_xsens.c +++ b/sw/airborne/modules/ins/ins_xsens.c @@ -71,7 +71,22 @@ INS_FORMAT ins_mz; float ins_pitch_neutral; float ins_roll_neutral; -volatile uint8_t new_ins_attitude; +//volatile uint8_t new_ins_attitude; + +#include "subsystems/imu.h" + +void ahrs_init(void) +{ + ins_init(); +} + +void imu_periodic(void) +{ + ins_periodic_task(); +} + +//struct Imu imu; + ////////////////////////////////////////////////////////////////////////////////////////// // diff --git a/sw/airborne/modules/ins/ins_xsens.h b/sw/airborne/modules/ins/ins_xsens.h index 790e65bf5a..959aa16e86 100644 --- a/sw/airborne/modules/ins/ins_xsens.h +++ b/sw/airborne/modules/ins/ins_xsens.h @@ -31,6 +31,8 @@ #include "std.h" +#include "ins_module.h" + extern int8_t xsens_hour; extern int8_t xsens_min; extern int8_t xsens_sec; @@ -41,5 +43,10 @@ extern int8_t xsens_day; extern uint8_t xsens_msg_status; extern uint16_t xsens_time_stamp; +#define AhrsEvent(_ahrs_handler) { \ + LED_TOGGLE(3); \ + InsEventCheckAndHandle(handle_ins_msg()) \ +} + #endif From a0257f958f3edf249e60d762132b288b055e2155 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:06:03 +0100 Subject: [PATCH 106/112] Default Value To allow autotriggering of changable value --- sw/airborne/modules/digital_cam/dc.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/sw/airborne/modules/digital_cam/dc.c b/sw/airborne/modules/digital_cam/dc.c index 9e7f4e5f2e..605d2b75b5 100644 --- a/sw/airborne/modules/digital_cam/dc.c +++ b/sw/airborne/modules/digital_cam/dc.c @@ -36,7 +36,7 @@ float dc_circle_start_angle = 0; float dc_circle_last_block = 0; float dc_circle_max_blocks = 0; -float dc_gps_dist = 0; +float dc_gps_dist = 50; float dc_gps_next_dist = 0; float dc_gps_x = 0; float dc_gps_y = 0; From 81ab407a8607d2cf466f23ed8dd7443ddea398ec Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:22:40 +0100 Subject: [PATCH 107/112] Hiller-Bar Helicopter Stabilization Manual Mode (for safety pilot) --- conf/autopilot/rotorcraft.makefile | 1 + .../subsystems/rotorcraft/fdm_nps.makefile | 2 + .../firmwares/rotorcraft/stabilization.h | 2 + .../stabilization/stabilization_none.c | 69 +++++++++++++++++++ .../stabilization/stabilization_none.h | 37 ++++++++++ 5 files changed, 111 insertions(+) create mode 100644 sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c create mode 100644 sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h diff --git a/conf/autopilot/rotorcraft.makefile b/conf/autopilot/rotorcraft.makefile index a4d248a8be..d7aec02ce9 100644 --- a/conf/autopilot/rotorcraft.makefile +++ b/conf/autopilot/rotorcraft.makefile @@ -197,6 +197,7 @@ endif ap.srcs += $(SRC_FIRMWARE)/autopilot.c ap.srcs += $(SRC_FIRMWARE)/stabilization.c +ap.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_none.c ap.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_rate.c ap.CFLAGS += -DUSE_NAVIGATION diff --git a/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile b/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile index 00b92d675e..52f040875e 100644 --- a/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile +++ b/conf/autopilot/subsystems/rotorcraft/fdm_nps.makefile @@ -115,6 +115,8 @@ sim.srcs += $(SRC_FIRMWARE)/autopilot.c sim.srcs += $(SRC_FIRMWARE)/stabilization.c sim.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_rate.c +sim.srcs += $(SRC_FIRMWARE)/stabilization/stabilization_none.c + NUM_TYPE=integer #NUM_TYPE=float diff --git a/sw/airborne/firmwares/rotorcraft/stabilization.h b/sw/airborne/firmwares/rotorcraft/stabilization.h index b3c2d2d268..fae6fa0b06 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization.h +++ b/sw/airborne/firmwares/rotorcraft/stabilization.h @@ -28,9 +28,11 @@ #include "generated/airframe.h" +#include "firmwares/rotorcraft/stabilization/stabilization_none.h" #include "firmwares/rotorcraft/stabilization/stabilization_rate.h" #include "firmwares/rotorcraft/stabilization/stabilization_attitude.h" + extern void stabilization_init(void); extern int32_t stabilization_cmd[COMMANDS_NB]; diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c new file mode 100644 index 0000000000..760c5a0a0e --- /dev/null +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.c @@ -0,0 +1,69 @@ +/* + * $Id$ + * + * Copyright (C) 2008-2009 Antoine Drouin + * Copyright (C) 2010 Felix Ruess + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#include "firmwares/rotorcraft/stabilization.h" +#include "firmwares/rotorcraft/stabilization/stabilization_none.h" + +#include "subsystems/radio_control.h" +#include "generated/airframe.h" + +#define F_UPDATE_RES 9 +#define REF_DOT_FRAC 11 +#define REF_FRAC 16 + + +#define OFFSET_AND_ROUND(_a, _b) (((_a)+(1<<((_b)-1)))>>(_b)) +#define OFFSET_AND_ROUND2(_a, _b) (((_a)+(1<<((_b)-1))-((_a)<0?1:0))>>(_b)) + +struct Int32Rates stabilization_none_rc_cmd; + +void stabilization_none_init(void) { + + INT_RATES_ZERO(stabilization_none_rc_cmd); + +} + + +void stabilization_none_read_rc( void ) { + + + stabilization_none_rc_cmd.p = (int32_t)-radio_control.values[RADIO_ROLL]; + + stabilization_none_rc_cmd.q = (int32_t)radio_control.values[RADIO_PITCH]; + + stabilization_none_rc_cmd.r = (int32_t)-radio_control.values[RADIO_YAW]; +} + +void stabilization_none_enter(void) { + INT_RATES_ZERO(stabilization_none_rc_cmd); +} + +void stabilization_none_run(bool_t in_flight) { + + /* sum to final command */ + stabilization_cmd[COMMAND_ROLL] = stabilization_none_rc_cmd.p * SUPERVISION_SCALE / MAX_PPRZ; + stabilization_cmd[COMMAND_PITCH] = stabilization_none_rc_cmd.q * SUPERVISION_SCALE / MAX_PPRZ; + stabilization_cmd[COMMAND_YAW] = stabilization_none_rc_cmd.r * SUPERVISION_SCALE / MAX_PPRZ; + +} diff --git a/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h new file mode 100644 index 0000000000..515d4e844a --- /dev/null +++ b/sw/airborne/firmwares/rotorcraft/stabilization/stabilization_none.h @@ -0,0 +1,37 @@ +/* + * $Id$ + * + * Copyright (C) 2008-2009 Antoine Drouin + * + * This file is part of paparazzi. + * + * paparazzi is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2, or (at your option) + * any later version. + * + * paparazzi is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with paparazzi; see the file COPYING. If not, write to + * the Free Software Foundation, 59 Temple Place - Suite 330, + * Boston, MA 02111-1307, USA. + */ + +#ifndef STABILIZATION_NONE +#define STABILIZATION_NONE + +#include "math/pprz_algebra_int.h" + +extern void stabilization_none_init(void); +extern void stabilization_none_read_rc(void); +extern void stabilization_none_run(bool_t in_flight); +extern void stabilization_none_enter(void); + +extern struct Int32Rates stabilization_none_rc_cmd; + + +#endif /* STABILIZATION_NONE */ From f4d6a1ff47be028f5527cf8901806e46f7684fae Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:24:10 +0100 Subject: [PATCH 108/112] Ignore new compiled files from openlog module --- .gitignore | 1 + 1 file changed, 1 insertion(+) diff --git a/.gitignore b/.gitignore index 78379d4bf0..b50369e075 100644 --- a/.gitignore +++ b/.gitignore @@ -129,6 +129,7 @@ /sw/logalizer/ivy_example /sw/logalizer/motor_bench /sw/logalizer/tmclient +/sw/logalizer/openlog2tlm # /sw/simulator/ /sw/simulator/gaia From 46a42d7557fbfdce88e184ba9d0816e4a167c77b Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:42:18 +0100 Subject: [PATCH 109/112] Run XSens as subsystem=ins_xsens with simulation capability --- .../subsystems/fixedwing/ins_xsens.makefile | 79 +++++++++++++++++++ sw/airborne/ap_downlink.h | 26 +++--- .../firmwares/rotorcraft/stabilization.c | 1 + 3 files changed, 93 insertions(+), 13 deletions(-) create mode 100644 conf/autopilot/subsystems/fixedwing/ins_xsens.makefile diff --git a/conf/autopilot/subsystems/fixedwing/ins_xsens.makefile b/conf/autopilot/subsystems/fixedwing/ins_xsens.makefile new file mode 100644 index 0000000000..2e3e92f26c --- /dev/null +++ b/conf/autopilot/subsystems/fixedwing/ins_xsens.makefile @@ -0,0 +1,79 @@ +# Hey Emacs, this is a -*- makefile -*- + +# XSens Mti-G + +# +# +# + + + +######################################### +## ATTITUDE + +ifeq ($(TARGET), ap) + +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# +# + +# ImuEvent -> XSensEvent +ap.CFLAGS += -DUSE_AHRS +ap.CFLAGS += -DIMU_TYPE_H=\"modules/ins/ins_xsens.h\" + +# AHRS Results +ap.CFLAGS += -DAHRS_TYPE_H=\"modules/ins/ins_xsens.h\" +ap.CFLAGS += -DINS_MODULE_H=\"modules/ins/ins_xsens.h\" + +ap.CFLAGS += -DUSE_UART$(XSENS_UART_NR) +ap.CFLAGS += -DINS_LINK=Uart$(XSENS_UART_NR) +ap.CFLAGS += -DUART$(XSENS_UART_NR)_BAUD=B230400 +ap.CFLAGS += -DUSE_GPS_XSENS +ap.CFLAGS += -DUSE_GPS_XSENS_RAW_DATA +ap.CFLAGS += -DGPS_NB_CHANNELS=16 +ap.CFLAGS += -DXSENS_OUTPUT_MODE=0x1836 +ap.srcs += $(SRC_MODULES)/ins/ins_xsens.c +ap.CFLAGS += -DAHRS_TRIGGERED_ATTITUDE_LOOP + + +endif + + +ifeq ($(TARGET), sim) + +sim.CFLAGS += -DAHRS_TYPE_H=\"subsystems/ahrs/ahrs_sim.h\" +sim.CFLAGS += -DUSE_AHRS -DAHRS_UPDATE_FW_ESTIMATOR + +sim.srcs += $(SRC_SUBSYSTEMS)/ahrs.c +sim.srcs += $(SRC_SUBSYSTEMS)/ahrs/ahrs_sim.c + +endif + +######################################### +## GPS + +# ap.CFLAGS += -DGPS + +$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c + +sim.CFLAGS += -DUSE_GPS -DGPS_USE_LATLONG +sim.CFLAGS += -DGPS_TYPE_H=\"subsystems/gps/gps_sim.h\" +sim.srcs += $(SRC_SUBSYSTEMS)/gps/gps_sim.c + + + + + diff --git a/sw/airborne/ap_downlink.h b/sw/airborne/ap_downlink.h index 85ef723bc2..cf830eca10 100644 --- a/sw/airborne/ap_downlink.h +++ b/sw/airborne/ap_downlink.h @@ -148,18 +148,6 @@ #define PERIODIC_SEND_SEGMENT(_chan) if (nav_in_segment) { DOWNLINK_SEND_SEGMENT(_chan, &nav_segment_x_1, &nav_segment_y_1, &nav_segment_x_2, &nav_segment_y_2); } #ifdef IMU_TYPE_H -# include "subsystems/imu.h" -# define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) { DOWNLINK_SEND_IMU_ACCEL_RAW(_chan, &imu.accel_unscaled.x, &imu.accel_unscaled.y, &imu.accel_unscaled.z)} -# define PERIODIC_SEND_IMU_GYRO_RAW(_chan) { DOWNLINK_SEND_IMU_GYRO_RAW(_chan, &imu.gyro_unscaled.p, &imu.gyro_unscaled.q, &imu.gyro_unscaled.r)} -# define PERIODIC_SEND_IMU_MAG_RAW(_chan) { DOWNLINK_SEND_IMU_MAG_RAW(_chan, &imu.mag_unscaled.x, &imu.mag_unscaled.y, &imu.mag_unscaled.z)} -# define PERIODIC_SEND_IMU_ACCEL(_chan) { struct FloatVect3 accel_float; ACCELS_FLOAT_OF_BFP(accel_float, imu.accel); DOWNLINK_SEND_IMU_ACCEL(_chan, &accel_float.x, &accel_float.y, &accel_float.z)} -# define PERIODIC_SEND_IMU_GYRO(_chan) { struct FloatRates gyro_float; RATES_FLOAT_OF_BFP(gyro_float, imu.gyro); DOWNLINK_SEND_IMU_GYRO(_chan, &gyro_float.p, &gyro_float.q, &gyro_float.r)} -# ifdef USE_MAGNETOMETER -# define PERIODIC_SEND_IMU_MAG(_chan) { struct FloatVect3 mag_float; MAGS_FLOAT_OF_BFP(mag_float, imu.mag); DOWNLINK_SEND_IMU_MAG(_chan, &mag_float.x, &mag_float.y, &mag_float.z)} -# else -# define PERIODIC_SEND_IMU_MAG(_chan) {} -# endif -#else # ifdef INS_MODULE_H # include "modules/ins/ins_module.h" # define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) {} @@ -169,13 +157,25 @@ # define PERIODIC_SEND_IMU_ACCEL(_chan) { DOWNLINK_SEND_IMU_ACCEL(_chan, &ins_ax, &ins_ay, &ins_az)} # define PERIODIC_SEND_IMU_MAG(_chan) { DOWNLINK_SEND_IMU_MAG(_chan, &ins_mx, &ins_my, &ins_mz)} # else +# include "subsystems/imu.h" +# define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) { DOWNLINK_SEND_IMU_ACCEL_RAW(_chan, &imu.accel_unscaled.x, &imu.accel_unscaled.y, &imu.accel_unscaled.z)} +# define PERIODIC_SEND_IMU_GYRO_RAW(_chan) { DOWNLINK_SEND_IMU_GYRO_RAW(_chan, &imu.gyro_unscaled.p, &imu.gyro_unscaled.q, &imu.gyro_unscaled.r)} +# define PERIODIC_SEND_IMU_MAG_RAW(_chan) { DOWNLINK_SEND_IMU_MAG_RAW(_chan, &imu.mag_unscaled.x, &imu.mag_unscaled.y, &imu.mag_unscaled.z)} +# define PERIODIC_SEND_IMU_ACCEL(_chan) { struct FloatVect3 accel_float; ACCELS_FLOAT_OF_BFP(accel_float, imu.accel); DOWNLINK_SEND_IMU_ACCEL(_chan, &accel_float.x, &accel_float.y, &accel_float.z)} +# define PERIODIC_SEND_IMU_GYRO(_chan) { struct FloatRates gyro_float; RATES_FLOAT_OF_BFP(gyro_float, imu.gyro); DOWNLINK_SEND_IMU_GYRO(_chan, &gyro_float.p, &gyro_float.q, &gyro_float.r)} +# ifdef USE_MAGNETOMETER +# define PERIODIC_SEND_IMU_MAG(_chan) { struct FloatVect3 mag_float; MAGS_FLOAT_OF_BFP(mag_float, imu.mag); DOWNLINK_SEND_IMU_MAG(_chan, &mag_float.x, &mag_float.y, &mag_float.z)} +# else +# define PERIODIC_SEND_IMU_MAG(_chan) {} +# endif +# endif +#else # define PERIODIC_SEND_IMU_ACCEL_RAW(_chan) {} # define PERIODIC_SEND_IMU_GYRO_RAW(_chan) {} # define PERIODIC_SEND_IMU_MAG_RAW(_chan) {} # define PERIODIC_SEND_IMU_ACCEL(_chan) {} # define PERIODIC_SEND_IMU_GYRO(_chan) {} # define PERIODIC_SEND_IMU_MAG(_chan) {} -# endif #endif #ifdef IMU_ANALOG diff --git a/sw/airborne/firmwares/rotorcraft/stabilization.c b/sw/airborne/firmwares/rotorcraft/stabilization.c index f273b4e76c..449d30eff3 100644 --- a/sw/airborne/firmwares/rotorcraft/stabilization.c +++ b/sw/airborne/firmwares/rotorcraft/stabilization.c @@ -27,6 +27,7 @@ int32_t stabilization_cmd[COMMANDS_NB]; void stabilization_init(void) { #ifndef STABILIZATION_SKIP_RATE + stabilization_none_init(); stabilization_rate_init(); #endif stabilization_attitude_init(); From 849e25b9e9a538ae311829d0e994b88c0bb0ae0d Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:44:58 +0100 Subject: [PATCH 110/112] Line Endings Corrected --- conf/airframes/CDW/LisaAspirin2.xml | 2 +- conf/messages.xml | 2 +- sw/airborne/modules/openlog/openlog.c | 4 ++-- sw/airborne/modules/openlog/openlog.h | 6 +++--- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/conf/airframes/CDW/LisaAspirin2.xml b/conf/airframes/CDW/LisaAspirin2.xml index 807bd309d8..d79308e98b 100644 --- a/conf/airframes/CDW/LisaAspirin2.xml +++ b/conf/airframes/CDW/LisaAspirin2.xml @@ -206,7 +206,7 @@ - + diff --git a/conf/messages.xml b/conf/messages.xml index 982ce3b37f..b4a3661036 100644 --- a/conf/messages.xml +++ b/conf/messages.xml @@ -943,7 +943,7 @@ - + diff --git a/sw/airborne/modules/openlog/openlog.c b/sw/airborne/modules/openlog/openlog.c index 3b62e2aa14..e2b8532151 100755 --- a/sw/airborne/modules/openlog/openlog.c +++ b/sw/airborne/modules/openlog/openlog.c @@ -23,8 +23,8 @@ */ /** - * This module provides a timestamp-message, allowing - * sw/logalizer/openlog2tlm to convert a recorded dumpfile, + * This module provides a timestamp-message, allowing + * sw/logalizer/openlog2tlm to convert a recorded dumpfile, * created by openlog into the pprz-tlm format, to be converted into * .data and .log files by sw/logalizer/sd2log */ diff --git a/sw/airborne/modules/openlog/openlog.h b/sw/airborne/modules/openlog/openlog.h index 9c86ba49ca..8c2e5ca70c 100755 --- a/sw/airborne/modules/openlog/openlog.h +++ b/sw/airborne/modules/openlog/openlog.h @@ -23,10 +23,10 @@ */ /** \file openlog.h - * This module provides a timestamp-message, allowing - * sw/logalizer/openlog2tlm to convert a recorded dumpfile, + * This module provides a timestamp-message, allowing + * sw/logalizer/openlog2tlm to convert a recorded dumpfile, * created by openlog into the pprz-tlm format, to be converted into - * .data and .log files by sw/logalizer/sd2log + * .data and .log files by sw/logalizer/sd2log */ #ifndef OPENLOG_H From ccf19c803fb821d5a1a2b7ac36112eb3cb6d0e8e Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 15:58:02 +0100 Subject: [PATCH 111/112] Removed outdated files: use subsystem ins_xsens now --- .../subsystems/fixedwing/gps_xsens.makefile | 9 ------- conf/modules/ins_xsens_MTiG_fixedwing.xml | 26 ------------------- 2 files changed, 35 deletions(-) delete mode 100644 conf/autopilot/subsystems/fixedwing/gps_xsens.makefile delete mode 100644 conf/modules/ins_xsens_MTiG_fixedwing.xml diff --git a/conf/autopilot/subsystems/fixedwing/gps_xsens.makefile b/conf/autopilot/subsystems/fixedwing/gps_xsens.makefile deleted file mode 100644 index 0d5dba7efd..0000000000 --- a/conf/autopilot/subsystems/fixedwing/gps_xsens.makefile +++ /dev/null @@ -1,9 +0,0 @@ -# Hey Emacs, this is a -*- makefile -*- - -# XSens Mti-G - - -# ap.CFLAGS += -DGPS - -$(TARGET).srcs += $(SRC_SUBSYSTEMS)/gps.c - diff --git a/conf/modules/ins_xsens_MTiG_fixedwing.xml b/conf/modules/ins_xsens_MTiG_fixedwing.xml deleted file mode 100644 index 6ff0911806..0000000000 --- a/conf/modules/ins_xsens_MTiG_fixedwing.xml +++ /dev/null @@ -1,26 +0,0 @@ - - - - - -
- -
- - - - - - - - - - - - - - - - -
- From cd8247589a08701d07fa9150d40f4ffde5db52f0 Mon Sep 17 00:00:00 2001 From: Christophe De Wagter Date: Mon, 5 Mar 2012 16:37:49 +0100 Subject: [PATCH 112/112] positive commands: right-roll up right-yaw --- conf/radios/R6107SP_7ch_xyz.xml | 53 +++++++++++++++++++++++++++++++++ 1 file changed, 53 insertions(+) create mode 100644 conf/radios/R6107SP_7ch_xyz.xml diff --git a/conf/radios/R6107SP_7ch_xyz.xml b/conf/radios/R6107SP_7ch_xyz.xml new file mode 100644 index 0000000000..75c4b48190 --- /dev/null +++ b/conf/radios/R6107SP_7ch_xyz.xml @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + +